Skip to content

Commit

Permalink
Switch to std::bind (#2967)
Browse files Browse the repository at this point in the history
* boost::bind -> std::bind
  grep -rlI --exclude-dir=.git "boost::bind" | xargs sed -i 's/boost::bind/std::bind/g'
* Convert bind placeholders
  grep -rlI --exclude-dir=.git " _[0-9]" | xargs sed -i 's/ _\([0-9]\)/ std::placeholders::_\1/g'
* Update bind include header
  grep -rlI --exclude-dir=.git "boost/bind" | xargs sed -i 's#boost/bind.hpp#functional#'
  • Loading branch information
jspricke committed Nov 18, 2021
1 parent 928afab commit ab42a1d
Show file tree
Hide file tree
Showing 69 changed files with 411 additions and 352 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ BackgroundProcessing::BackgroundProcessing()
// spin a thread that will process user events
run_processing_thread_ = true;
processing_ = false;
processing_thread_ = std::make_unique<boost::thread>(boost::bind(&BackgroundProcessing::processingThread, this));
processing_thread_ = std::make_unique<boost::thread>(std::bind(&BackgroundProcessing::processingThread, this));
}

BackgroundProcessing::~BackgroundProcessing()
Expand Down
4 changes: 2 additions & 2 deletions moveit_core/collision_detection/src/collision_matrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Ioan Sucan, E. Gil Jones */

#include <moveit/collision_detection/collision_matrix.h>
#include <boost/bind.hpp>
#include <functional>
#include <iomanip>

namespace collision_detection
Expand Down Expand Up @@ -268,7 +268,7 @@ bool AllowedCollisionMatrix::getAllowedCollision(const std::string& name1, const
else if (!found1 && found2)
fn = fn2;
else if (found1 && found2)
fn = boost::bind(&andDecideContact, fn1, fn2, _1);
fn = std::bind(&andDecideContact, fn1, fn2, std::placeholders::_1);
else
return false;
return true;
Expand Down
14 changes: 9 additions & 5 deletions moveit_core/collision_detection/src/world_diff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Acorn Pooley, Ioan Sucan */

#include <moveit/collision_detection/world_diff.h>
#include <boost/bind.hpp>
#include <functional>

namespace collision_detection
{
Expand All @@ -52,7 +52,8 @@ WorldDiff::WorldDiff()

WorldDiff::WorldDiff(const WorldPtr& world) : world_(world)
{
observer_handle_ = world->addObserver(boost::bind(&WorldDiff::notify, this, _1, _2));
observer_handle_ =
world->addObserver(std::bind(&WorldDiff::notify, this, std::placeholders::_1, std::placeholders::_2));
}

WorldDiff::WorldDiff(WorldDiff& other)
Expand All @@ -63,7 +64,8 @@ WorldDiff::WorldDiff(WorldDiff& other)
changes_ = other.changes_;

WorldWeakPtr(world).swap(world_);
observer_handle_ = world->addObserver(boost::bind(&WorldDiff::notify, this, _1, _2));
observer_handle_ =
world->addObserver(std::bind(&WorldDiff::notify, this, std::placeholders::_1, std::placeholders::_2));
}
}

Expand All @@ -87,7 +89,8 @@ void WorldDiff::reset(const WorldPtr& world)
old_world->removeObserver(observer_handle_);

WorldWeakPtr(world).swap(world_);
observer_handle_ = world->addObserver(boost::bind(&WorldDiff::notify, this, _1, _2));
observer_handle_ =
world->addObserver(std::bind(&WorldDiff::notify, this, std::placeholders::_1, std::placeholders::_2));
}

void WorldDiff::setWorld(const WorldPtr& world)
Expand All @@ -101,7 +104,8 @@ void WorldDiff::setWorld(const WorldPtr& world)

WorldWeakPtr(world).swap(world_);

observer_handle_ = world->addObserver(boost::bind(&WorldDiff::notify, this, _1, _2));
observer_handle_ =
world->addObserver(std::bind(&WorldDiff::notify, this, std::placeholders::_1, std::placeholders::_2));
world->notifyObserverAllObjects(observer_handle_, World::CREATE | World::ADD_SHAPE);
}

Expand Down
10 changes: 5 additions & 5 deletions moveit_core/collision_detection/test/test_world.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
#include <gtest/gtest.h>
#include <moveit/collision_detection/world.h>
#include <geometric_shapes/shapes.h>
#include <boost/bind.hpp>
#include <functional>

TEST(World, AddRemoveShape)
{
Expand Down Expand Up @@ -236,7 +236,7 @@ TEST(World, TrackChanges)

TestAction ta;
collision_detection::World::ObserverHandle observer_ta;
observer_ta = world.addObserver(boost::bind(TrackChangesNotify, &ta, _1, _2));
observer_ta = world.addObserver(std::bind(TrackChangesNotify, &ta, std::placeholders::_1, std::placeholders::_2));

// Create some shapes
shapes::ShapePtr ball(new shapes::Sphere(1.0));
Expand Down Expand Up @@ -267,7 +267,7 @@ TEST(World, TrackChanges)

TestAction ta2;
collision_detection::World::ObserverHandle observer_ta2;
observer_ta2 = world.addObserver(boost::bind(TrackChangesNotify, &ta2, _1, _2));
observer_ta2 = world.addObserver(std::bind(TrackChangesNotify, &ta2, std::placeholders::_1, std::placeholders::_2));

world.addToObject("obj2", cyl, Eigen::Isometry3d::Identity());

Expand Down Expand Up @@ -305,7 +305,7 @@ TEST(World, TrackChanges)

TestAction ta3;
collision_detection::World::ObserverHandle observer_ta3;
observer_ta3 = world.addObserver(boost::bind(TrackChangesNotify, &ta3, _1, _2));
observer_ta3 = world.addObserver(std::bind(TrackChangesNotify, &ta3, std::placeholders::_1, std::placeholders::_2));

bool rm_good = world.removeShapeFromObject("obj2", cyl);
EXPECT_TRUE(rm_good);
Expand Down Expand Up @@ -371,7 +371,7 @@ TEST(World, ObjectPoseAndSubframes)

TestAction ta;
collision_detection::World::ObserverHandle observer_ta;
observer_ta = world.addObserver(boost::bind(TrackChangesNotify, &ta, _1, _2));
observer_ta = world.addObserver(std::bind(TrackChangesNotify, &ta, std::placeholders::_1, std::placeholders::_2));

// Create shapes
shapes::ShapePtr ball(new shapes::Sphere(1.0));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
#include <moveit/collision_detection_bullet/collision_detector_allocator_bullet.h>
#include <moveit/collision_detection_bullet/bullet_integration/ros_bullet_utils.h>
#include <moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h>
#include <boost/bind.hpp>
#include <functional>
#include <bullet/btBulletCollisionCommon.h>

namespace collision_detection
Expand All @@ -54,7 +54,8 @@ CollisionEnvBullet::CollisionEnvBullet(const moveit::core::RobotModelConstPtr& m
: CollisionEnv(model, padding, scale)
{
// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvBullet::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvBullet::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

for (const std::pair<const std::string, urdf::LinkSharedPtr>& link : robot_model_->getURDF()->links_)
{
Expand All @@ -67,7 +68,8 @@ CollisionEnvBullet::CollisionEnvBullet(const moveit::core::RobotModelConstPtr& m
: CollisionEnv(model, world, padding, scale)
{
// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvBullet::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvBullet::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

for (const std::pair<const std::string, urdf::LinkSharedPtr>& link : robot_model_->getURDF()->links_)
{
Expand All @@ -81,7 +83,8 @@ CollisionEnvBullet::CollisionEnvBullet(const CollisionEnvBullet& other, const Wo
: CollisionEnv(other, world)
{
// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvBullet::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvBullet::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

for (const std::pair<const std::string, urdf::LinkSharedPtr>& link : other.robot_model_->getURDF()->links_)
{
Expand Down Expand Up @@ -304,7 +307,8 @@ void CollisionEnvBullet::setWorld(const WorldPtr& world)
CollisionEnv::setWorld(world);

// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvBullet::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvBullet::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

// get notifications any objects already in the new world
getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
Expand Down
12 changes: 8 additions & 4 deletions moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,8 @@ CollisionEnvFCL::CollisionEnvFCL(const moveit::core::RobotModelConstPtr& model,
manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();

// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvFCL::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvFCL::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));
}

CollisionEnvFCL::CollisionEnvFCL(const moveit::core::RobotModelConstPtr& model, const WorldPtr& world, double padding,
Expand Down Expand Up @@ -140,7 +141,8 @@ CollisionEnvFCL::CollisionEnvFCL(const moveit::core::RobotModelConstPtr& model,
manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();

// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvFCL::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvFCL::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));
getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
}

Expand All @@ -162,7 +164,8 @@ CollisionEnvFCL::CollisionEnvFCL(const CollisionEnvFCL& other, const WorldPtr& w
// manager_->update();

// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvFCL::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvFCL::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));
}

void CollisionEnvFCL::getAttachedBodyObjects(const moveit::core::AttachedBody* ab,
Expand Down Expand Up @@ -403,7 +406,8 @@ void CollisionEnvFCL::setWorld(const WorldPtr& world)
CollisionEnv::setWorld(world);

// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvFCL::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvFCL::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

// get notifications any objects already in the new world
getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include <moveit/collision_distance_field/collision_common_distance_field.h>
#include <moveit/distance_field/propagation_distance_field.h>
#include <moveit/collision_distance_field/collision_detector_allocator_distance_field.h>
#include <boost/bind.hpp>
#include <functional>
#include <memory>
#include <utility>

Expand All @@ -69,7 +69,8 @@ CollisionEnvDistanceField::CollisionEnvDistanceField(
distance_field_cache_entry_world_ = generateDistanceFieldCacheEntryWorld();

// request notifications about changes to world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvDistanceField::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvDistanceField::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));
}

CollisionEnvDistanceField::CollisionEnvDistanceField(
Expand All @@ -85,7 +86,8 @@ CollisionEnvDistanceField::CollisionEnvDistanceField(
distance_field_cache_entry_world_ = generateDistanceFieldCacheEntryWorld();

// request notifications about changes to world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvDistanceField::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvDistanceField::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
}
Expand All @@ -108,7 +110,8 @@ CollisionEnvDistanceField::CollisionEnvDistanceField(const CollisionEnvDistanceF
planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);

// request notifications about changes to world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvDistanceField::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvDistanceField::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));
getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
}

Expand Down Expand Up @@ -1705,7 +1708,8 @@ void CollisionEnvDistanceField::setWorld(const WorldPtr& world)
CollisionEnv::setWorld(world);

// request notifications about changes to new world
observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvDistanceField::notifyObjectChange, this, _1, _2));
observer_handle_ = getWorld()->addObserver(
std::bind(&CollisionEnvDistanceField::notifyObjectChange, this, std::placeholders::_1, std::placeholders::_2));

// get notifications any objects already in the new world
getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

#include <moveit/constraint_samplers/default_constraint_samplers.h>
#include <cassert>
#include <boost/bind.hpp>
#include <functional>

namespace constraint_samplers
{
Expand Down Expand Up @@ -565,8 +565,8 @@ bool IKConstraintSampler::sampleHelper(moveit::core::RobotState& state, const mo

kinematics::KinematicsBase::IKCallbackFn adapted_ik_validity_callback;
if (group_state_validity_callback_)
adapted_ik_validity_callback =
boost::bind(&samplingIkCallbackFnAdapter, &state, jmg_, group_state_validity_callback_, _1, _2, _3);
adapted_ik_validity_callback = std::bind(&samplingIkCallbackFnAdapter, &state, jmg_, group_state_validity_callback_,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3);

for (unsigned int a = 0; a < max_attempts; ++a)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@
#include <gtest/gtest.h>
#include <urdf_parser/urdf_parser.h>
#include <fstream>
#include <boost/bind.hpp>
#include <functional>

#include "pr2_arm_kinematics_plugin.h"

Expand Down Expand Up @@ -82,8 +82,8 @@ class LoadPlanningModelsPr2 : public testing::Test
pr2_kinematics_plugin_left_arm_->initialize(*robot_model_, "left_arm", "torso_lift_link", { "l_wrist_roll_link" },
.01);

func_right_arm_ = boost::bind(&LoadPlanningModelsPr2::getKinematicsSolverRightArm, this, _1);
func_left_arm_ = boost::bind(&LoadPlanningModelsPr2::getKinematicsSolverLeftArm, this, _1);
func_right_arm_ = std::bind(&LoadPlanningModelsPr2::getKinematicsSolverRightArm, this, std::placeholders::_1);
func_left_arm_ = std::bind(&LoadPlanningModelsPr2::getKinematicsSolverLeftArm, this, std::placeholders::_1);

std::map<std::string, moveit::core::SolverAllocatorFn> allocators;
allocators["right_arm"] = func_right_arm_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include <geometric_shapes/check_isometry.h>
#include <boost/math/constants/constants.hpp>
#include <tf2_eigen/tf2_eigen.h>
#include <boost/bind.hpp>
#include <functional>
#include <limits>
#include <memory>

Expand Down Expand Up @@ -1112,7 +1112,7 @@ ConstraintEvaluationResult VisibilityConstraint::decide(const moveit::core::Robo
collision_detection::CollisionRequest req;
collision_detection::CollisionResult res;
collision_detection::AllowedCollisionMatrix acm;
acm.setDefaultEntry("cone", boost::bind(&VisibilityConstraint::decideContact, this, _1));
acm.setDefaultEntry("cone", std::bind(&VisibilityConstraint::decideContact, this, std::placeholders::_1));
req.contacts = true;
req.verbose = verbose;
req.max_contacts = 1;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Ioan Sucan */

#include <moveit/planning_request_adapter/planning_request_adapter.h>
#include <boost/bind.hpp>
#include <functional>
#include <algorithm>

// we could really use some c++11 lambda functions here :)
Expand Down Expand Up @@ -63,8 +63,9 @@ bool PlanningRequestAdapter::adaptAndPlan(const planning_interface::PlannerManag
planning_interface::MotionPlanResponse& res,
std::vector<std::size_t>& added_path_index) const
{
return adaptAndPlan(boost::bind(&callPlannerInterfaceSolve, planner.get(), _1, _2, _3), planning_scene, req, res,
added_path_index);
return adaptAndPlan(std::bind(&callPlannerInterfaceSolve, planner.get(), std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3),
planning_scene, req, res, added_path_index);
}

bool PlanningRequestAdapter::adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
Expand Down Expand Up @@ -145,10 +146,12 @@ bool PlanningRequestAdapterChain::adaptAndPlan(const planning_interface::Planner

// if there are adapters, construct a function pointer for each, in order,
// so that in the end we have a nested sequence of function pointers that call the adapters in the correct order.
PlanningRequestAdapter::PlannerFn fn = boost::bind(&callAdapter1, adapters_.back().get(), planner, _1, _2, _3,
boost::ref(added_path_index_each.back()));
PlanningRequestAdapter::PlannerFn fn =
std::bind(&callAdapter1, adapters_.back().get(), planner, std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3, boost::ref(added_path_index_each.back()));
for (int i = adapters_.size() - 2; i >= 0; --i)
fn = boost::bind(&callAdapter2, adapters_[i].get(), fn, _1, _2, _3, boost::ref(added_path_index_each[i]));
fn = std::bind(&callAdapter2, adapters_[i].get(), fn, std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3, boost::ref(added_path_index_each[i]));
bool result = fn(planning_scene, req, res);
added_path_index.clear();

Expand Down
8 changes: 5 additions & 3 deletions moveit_core/robot_state/src/robot_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
#include <moveit/backtrace/backtrace.h>
#include <moveit/profiler/profiler.h>
#include <moveit/macros/console_colors.h>
#include <boost/bind.hpp>
#include <functional>
#include <moveit/robot_model/aabb.h>

namespace moveit
Expand Down Expand Up @@ -1780,7 +1780,8 @@ bool RobotState::setFromIK(const JointModelGroup* jmg, const EigenSTL::vector_Is
// set callback function
kinematics::KinematicsBase::IKCallbackFn ik_callback_fn;
if (constraint)
ik_callback_fn = boost::bind(&ikCallbackFnAdapter, this, jmg, constraint, _1, _2, _3);
ik_callback_fn = std::bind(&ikCallbackFnAdapter, this, jmg, constraint, std::placeholders::_1,
std::placeholders::_2, std::placeholders::_3);

// Bijection
const std::vector<unsigned int>& bij = jmg->getKinematicsSolverJointBijection();
Expand Down Expand Up @@ -1923,7 +1924,8 @@ bool RobotState::setFromIKSubgroups(const JointModelGroup* jmg, const EigenSTL::
std::vector<geometry_msgs::Pose> ik_queries(poses_in.size());
kinematics::KinematicsBase::IKCallbackFn ik_callback_fn;
if (constraint)
ik_callback_fn = boost::bind(&ikCallbackFnAdapter, this, jmg, constraint, _1, _2, _3);
ik_callback_fn = std::bind(&ikCallbackFnAdapter, this, jmg, constraint, std::placeholders::_1,
std::placeholders::_2, std::placeholders::_3);

for (std::size_t i = 0; i < transformed_poses.size(); ++i)
{
Expand Down
Loading

0 comments on commit ab42a1d

Please sign in to comment.