Skip to content

Commit

Permalink
std::bind and placeholders instead of boost
Browse files Browse the repository at this point in the history
  • Loading branch information
lucasw authored and bmagyar committed May 19, 2022
1 parent 5e4075b commit e2aaddf
Show file tree
Hide file tree
Showing 5 changed files with 7 additions and 11 deletions.
4 changes: 1 addition & 3 deletions ackermann_steering_controller/src/odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,6 @@

#include <ackermann_steering_controller/odometry.h>

#include <boost/bind/bind.hpp>

namespace ackermann_steering_controller
{
namespace bacc = boost::accumulators;
Expand All @@ -61,7 +59,7 @@ namespace ackermann_steering_controller
, velocity_rolling_window_size_(velocity_rolling_window_size)
, linear_acc_(RollingWindow::window_size = velocity_rolling_window_size)
, angular_acc_(RollingWindow::window_size = velocity_rolling_window_size)
, integrate_fun_(boost::bind(&Odometry::integrateExact, this, boost::placeholders::_1, boost::placeholders::_2))
, integrate_fun_(std::bind(&Odometry::integrateExact, this, std::placeholders::_1, std::placeholders::_2))
{
}

Expand Down
2 changes: 1 addition & 1 deletion diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -383,7 +383,7 @@ namespace diff_drive_controller{
dyn_reconf_server_mutex_.unlock();

dyn_reconf_server_->setCallback(
boost::bind(&DiffDriveController::reconfCallback, this, boost::placeholders::_1, boost::placeholders::_2));
std::bind(&DiffDriveController::reconfCallback, this, std::placeholders::_1, std::placeholders::_2));

return true;
}
Expand Down
4 changes: 1 addition & 3 deletions diff_drive_controller/src/odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,6 @@

#include <diff_drive_controller/odometry.h>

#include <boost/bind/bind.hpp>

namespace diff_drive_controller
{
namespace bacc = boost::accumulators;
Expand All @@ -62,7 +60,7 @@ namespace diff_drive_controller
, velocity_rolling_window_size_(velocity_rolling_window_size)
, linear_acc_(RollingWindow::window_size = velocity_rolling_window_size)
, angular_acc_(RollingWindow::window_size = velocity_rolling_window_size)
, integrate_fun_(boost::bind(&Odometry::integrateExact, this, boost::placeholders::_1, boost::placeholders::_2))
, integrate_fun_(std::bind(&Odometry::integrateExact, this, std::placeholders::_1, std::placeholders::_2))
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -214,8 +214,8 @@ bool GripperActionController<HardwareInterface>::init(HardwareInterface* hw,

// ROS API: Action interface
action_server_.reset(new ActionServer(
controller_nh_, "gripper_cmd", boost::bind(&GripperActionController::goalCB, this, boost::placeholders::_1),
boost::bind(&GripperActionController::cancelCB, this, boost::placeholders::_1), false));
controller_nh_, "gripper_cmd", std::bind(&GripperActionController::goalCB, this, std::placeholders::_1),
std::bind(&GripperActionController::cancelCB, this, std::placeholders::_1), false));
action_server_->start();
return true;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -295,8 +295,8 @@ bool JointTrajectoryController<SegmentImpl, HardwareInterface>::init(HardwareInt
// ROS API: Action interface
action_server_.reset(
new ActionServer(controller_nh_, "follow_joint_trajectory",
boost::bind(&JointTrajectoryController::goalCB, this, boost::placeholders::_1),
boost::bind(&JointTrajectoryController::cancelCB, this, boost::placeholders::_1), false));
std::bind(&JointTrajectoryController::goalCB, this, std::placeholders::_1),
std::bind(&JointTrajectoryController::cancelCB, this, std::placeholders::_1), false));
action_server_->start();

// ROS API: Provided services
Expand Down

0 comments on commit e2aaddf

Please sign in to comment.