diff --git a/moveit_core/background_processing/src/background_processing.cpp b/moveit_core/background_processing/src/background_processing.cpp index 5614aa514a..00df01de05 100644 --- a/moveit_core/background_processing/src/background_processing.cpp +++ b/moveit_core/background_processing/src/background_processing.cpp @@ -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::bind(&BackgroundProcessing::processingThread, this)); + processing_thread_ = std::make_unique(std::bind(&BackgroundProcessing::processingThread, this)); } BackgroundProcessing::~BackgroundProcessing() diff --git a/moveit_core/collision_detection/src/collision_matrix.cpp b/moveit_core/collision_detection/src/collision_matrix.cpp index 05ea5b66ba..369774ef18 100644 --- a/moveit_core/collision_detection/src/collision_matrix.cpp +++ b/moveit_core/collision_detection/src/collision_matrix.cpp @@ -35,7 +35,7 @@ /* Author: Ioan Sucan, E. Gil Jones */ #include -#include +#include #include namespace collision_detection @@ -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; diff --git a/moveit_core/collision_detection/src/world_diff.cpp b/moveit_core/collision_detection/src/world_diff.cpp index dcf75b6d4d..c43b9d920a 100644 --- a/moveit_core/collision_detection/src/world_diff.cpp +++ b/moveit_core/collision_detection/src/world_diff.cpp @@ -35,7 +35,7 @@ /* Author: Acorn Pooley, Ioan Sucan */ #include -#include +#include namespace collision_detection { @@ -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) @@ -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)); } } @@ -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) @@ -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); } diff --git a/moveit_core/collision_detection/test/test_world.cpp b/moveit_core/collision_detection/test/test_world.cpp index 126143dafc..824ce083f1 100644 --- a/moveit_core/collision_detection/test/test_world.cpp +++ b/moveit_core/collision_detection/test/test_world.cpp @@ -37,7 +37,7 @@ #include #include #include -#include +#include TEST(World, AddRemoveShape) { @@ -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)); @@ -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()); @@ -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); @@ -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)); diff --git a/moveit_core/collision_detection_bullet/src/collision_env_bullet.cpp b/moveit_core/collision_detection_bullet/src/collision_env_bullet.cpp index 3885f721dc..3e2ea9b1ab 100644 --- a/moveit_core/collision_detection_bullet/src/collision_env_bullet.cpp +++ b/moveit_core/collision_detection_bullet/src/collision_env_bullet.cpp @@ -38,7 +38,7 @@ #include #include #include -#include +#include #include namespace collision_detection @@ -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& link : robot_model_->getURDF()->links_) { @@ -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& link : robot_model_->getURDF()->links_) { @@ -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& link : other.robot_model_->getURDF()->links_) { @@ -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); diff --git a/moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp b/moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp index 4895b27baf..b549f179fb 100644 --- a/moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp +++ b/moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp @@ -105,7 +105,8 @@ CollisionEnvFCL::CollisionEnvFCL(const moveit::core::RobotModelConstPtr& model, manager_ = std::make_unique(); // 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, @@ -140,7 +141,8 @@ CollisionEnvFCL::CollisionEnvFCL(const moveit::core::RobotModelConstPtr& model, manager_ = std::make_unique(); // 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); } @@ -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, @@ -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); diff --git a/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp b/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp index dee29b010b..5e2c34bfbe 100644 --- a/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp +++ b/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp @@ -42,7 +42,7 @@ #include #include #include -#include +#include #include #include @@ -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( @@ -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); } @@ -108,7 +110,8 @@ CollisionEnvDistanceField::CollisionEnvDistanceField(const CollisionEnvDistanceF planning_scene_ = std::make_shared(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); } @@ -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); diff --git a/moveit_core/constraint_samplers/src/default_constraint_samplers.cpp b/moveit_core/constraint_samplers/src/default_constraint_samplers.cpp index 55ed6a618a..5d28e21206 100644 --- a/moveit_core/constraint_samplers/src/default_constraint_samplers.cpp +++ b/moveit_core/constraint_samplers/src/default_constraint_samplers.cpp @@ -36,7 +36,7 @@ #include #include -#include +#include namespace constraint_samplers { @@ -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) { diff --git a/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp b/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp index 3cfd3a957f..f01f1e188a 100644 --- a/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp +++ b/moveit_core/constraint_samplers/test/test_constraint_samplers.cpp @@ -49,7 +49,7 @@ #include #include #include -#include +#include #include "pr2_arm_kinematics_plugin.h" @@ -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 allocators; allocators["right_arm"] = func_right_arm_; diff --git a/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp b/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp index 2588bd4541..7c3629c3a9 100644 --- a/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp +++ b/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp @@ -42,7 +42,7 @@ #include #include #include -#include +#include #include #include @@ -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; diff --git a/moveit_core/planning_request_adapter/src/planning_request_adapter.cpp b/moveit_core/planning_request_adapter/src/planning_request_adapter.cpp index aa04e8a8c9..35fac2f52d 100644 --- a/moveit_core/planning_request_adapter/src/planning_request_adapter.cpp +++ b/moveit_core/planning_request_adapter/src/planning_request_adapter.cpp @@ -35,7 +35,7 @@ /* Author: Ioan Sucan */ #include -#include +#include #include // we could really use some c++11 lambda functions here :) @@ -63,8 +63,9 @@ bool PlanningRequestAdapter::adaptAndPlan(const planning_interface::PlannerManag planning_interface::MotionPlanResponse& res, std::vector& 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, @@ -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(); diff --git a/moveit_core/robot_state/src/robot_state.cpp b/moveit_core/robot_state/src/robot_state.cpp index c60cd509cc..3d74b0a439 100644 --- a/moveit_core/robot_state/src/robot_state.cpp +++ b/moveit_core/robot_state/src/robot_state.cpp @@ -44,7 +44,7 @@ #include #include #include -#include +#include #include namespace moveit @@ -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& bij = jmg->getKinematicsSolverJointBijection(); @@ -1923,7 +1924,8 @@ bool RobotState::setFromIKSubgroups(const JointModelGroup* jmg, const EigenSTL:: std::vector 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) { diff --git a/moveit_experimental/kinematics_constraint_aware/src/kinematics_constraint_aware.cpp b/moveit_experimental/kinematics_constraint_aware/src/kinematics_constraint_aware.cpp index b75ae595d2..b9fdc21666 100644 --- a/moveit_experimental/kinematics_constraint_aware/src/kinematics_constraint_aware.cpp +++ b/moveit_experimental/kinematics_constraint_aware/src/kinematics_constraint_aware.cpp @@ -41,7 +41,7 @@ #include #include #include -#include +#include namespace kinematics_constraint_aware { @@ -161,7 +161,8 @@ bool KinematicsConstraintAware::getIK(const planning_scene::PlanningSceneConstPt transformPoses(planning_scene, kinematic_state, request.pose_stamped_vector_, kinematic_model_->getModelFrame()); moveit::core::StateValidityCallbackFn constraint_callback_fn = - boost::bind(&KinematicsConstraintAware::validityCallbackFn, this, planning_scene, request, response, _1, _2); + std::bind(&KinematicsConstraintAware::validityCallbackFn, this, planning_scene, request, response, + std::placeholders::_1, std::placeholders::_2); bool result = false; if (has_sub_groups_) diff --git a/moveit_kinematics/test/test_kinematics_plugin.cpp b/moveit_kinematics/test/test_kinematics_plugin.cpp index 7ca176cd0b..60fc35b37f 100644 --- a/moveit_kinematics/test/test_kinematics_plugin.cpp +++ b/moveit_kinematics/test/test_kinematics_plugin.cpp @@ -37,7 +37,7 @@ #include #include -#include +#include #include #include #include @@ -592,7 +592,9 @@ TEST_F(KinematicsTest, searchIKWithCallback) } kinematics_solver_->searchPositionIK(poses[0], fk_values, timeout_, solution, - boost::bind(&KinematicsTest::searchIKCallback, this, _1, _2, _3), error_code); + std::bind(&KinematicsTest::searchIKCallback, this, std::placeholders::_1, + std::placeholders::_2, std::placeholders::_3), + error_code); if (error_code.val == error_code.SUCCESS) success++; else diff --git a/moveit_planners/ompl/ompl_interface/src/ompl_planner_manager.cpp b/moveit_planners/ompl/ompl_interface/src/ompl_planner_manager.cpp index 199c873ab9..c201a066fe 100644 --- a/moveit_planners/ompl/ompl_interface/src/ompl_planner_manager.cpp +++ b/moveit_planners/ompl/ompl_interface/src/ompl_planner_manager.cpp @@ -295,7 +295,7 @@ class OMPLPlannerManager : public planning_interface::PlannerManager pub_valid_states_ = nh_.advertise("ompl_planner_valid_states", 5); pub_valid_traj_ = nh_.advertise("ompl_planner_valid_trajectories", 5); display_random_valid_states_ = true; - // pub_valid_states_thread_.reset(new boost::thread(boost::bind(&OMPLPlannerManager::displayRandomValidStates, + // pub_valid_states_thread_.reset(new boost::thread(std::bind(&OMPLPlannerManager::displayRandomValidStates, // this))); } } diff --git a/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp b/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp index be1caeb2c6..d7c0bac0f6 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp @@ -63,8 +63,8 @@ void MoveGroupSequenceAction::initialize() ROS_INFO_STREAM("initialize move group sequence action"); move_action_server_ = std::make_unique>( root_node_handle_, "sequence_move_group", - boost::bind(&MoveGroupSequenceAction::executeSequenceCallback, this, _1), false); - move_action_server_->registerPreemptCallback(boost::bind(&MoveGroupSequenceAction::preemptMoveCallback, this)); + std::bind(&MoveGroupSequenceAction::executeSequenceCallback, this, std::placeholders::_1), false); + move_action_server_->registerPreemptCallback(std::bind(&MoveGroupSequenceAction::preemptMoveCallback, this)); move_action_server_->start(); command_list_manager_ = std::make_unique( @@ -137,10 +137,10 @@ void MoveGroupSequenceAction::executeSequenceCallbackPlanAndExecute( opt.replan_ = goal->planning_options.replan; opt.replan_attempts_ = goal->planning_options.replan_attempts; opt.replan_delay_ = goal->planning_options.replan_delay; - opt.before_execution_callback_ = boost::bind(&MoveGroupSequenceAction::startMoveExecutionCallback, this); + opt.before_execution_callback_ = std::bind(&MoveGroupSequenceAction::startMoveExecutionCallback, this); - opt.plan_callback_ = - boost::bind(&MoveGroupSequenceAction::planUsingSequenceManager, this, boost::cref(goal->request), _1); + opt.plan_callback_ = std::bind(&MoveGroupSequenceAction::planUsingSequenceManager, this, boost::cref(goal->request), + std::placeholders::_1); if (goal->planning_options.look_around && context_->plan_with_sensing_) { diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp index 93ba27e133..03694adf8f 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp @@ -74,8 +74,8 @@ bool pilz_industrial_motion_planner::computePoseIK(const planning_scene::Plannin rstate.setVariablePositions(seed); moveit::core::GroupStateValidityCallbackFn ik_constraint_function; - ik_constraint_function = - boost::bind(&pilz_industrial_motion_planner::isStateColliding, check_self_collision, scene, _1, _2, _3); + ik_constraint_function = std::bind(&pilz_industrial_motion_planner::isStateColliding, check_self_collision, scene, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); // call ik if (rstate.setFromIK(robot_model->getJointModelGroup(group_name), pose, link_name, timeout, ik_constraint_function)) diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_command_list_manager.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_command_list_manager.cpp index e7f1f01b99..fa596dcbc0 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_command_list_manager.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_command_list_manager.cpp @@ -624,13 +624,13 @@ TEST_F(IntegrationTestCommandListManager, TestGroupSpecificStartState) seq.erase(4, seq.size()); Gripper& gripper{ seq.getCmd(0) }; - gripper.getStartConfiguration().setCreateJointNameFunc(std::bind(&createGripperJointName, _1)); + gripper.getStartConfiguration().setCreateJointNameFunc(std::bind(&createGripperJointName, std::placeholders::_1)); // By deleting the model we guarantee that the start state only consists // of joints of the gripper group without the manipulator gripper.getStartConfiguration().clearModel(); PtpJointCart& ptp{ seq.getCmd(1) }; - ptp.getStartConfiguration().setCreateJointNameFunc(std::bind(&createManipulatorJointName, _1)); + ptp.getStartConfiguration().setCreateJointNameFunc(std::bind(&createManipulatorJointName, std::placeholders::_1)); // By deleting the model we guarantee that the start state only consists // of joints of the manipulator group without the gripper ptp.getStartConfiguration().clearModel(); diff --git a/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_sequence_service_capability.cpp b/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_sequence_service_capability.cpp index 2c04855230..5b5bdc7c73 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_sequence_service_capability.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/integrationtest_sequence_service_capability.cpp @@ -248,7 +248,9 @@ TEST_F(IntegrationTestSequenceService, TestSecondTrajInvalidStartState) // Set start state using std::placeholders::_1; - JointConfiguration config{ "MyGroupName", { -1., 2., -3., 4., -5., 0. }, std::bind(&createJointName, _1) }; + JointConfiguration config{ "MyGroupName", + { -1., 2., -3., 4., -5., 0. }, + std::bind(&createJointName, std::placeholders::_1) }; req_list.items[1].req.start_state.joint_state = config.toSensorMsg(); moveit_msgs::GetMotionSequence srv; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_functions.cpp index 4d4eb79ec3..30ce75d7a6 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_functions.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unittest_trajectory_functions.cpp @@ -456,7 +456,7 @@ TEST_P(TrajectoryFunctionsTestOnlyGripper, testComputePoseIKSelfCollisionForVali std::vector ik_state; std::transform(ik_actual1.begin(), ik_actual1.end(), std::back_inserter(ik_state), - boost::bind(&std::map::value_type::second, _1)); + std::bind(&std::map::value_type::second, std::placeholders::_1)); rstate.setJointGroupPositions(jmg, ik_state); rstate.update(); @@ -477,7 +477,7 @@ TEST_P(TrajectoryFunctionsTestOnlyGripper, testComputePoseIKSelfCollisionForVali std::vector ik_state2; std::transform(ik_actual2.begin(), ik_actual2.end(), std::back_inserter(ik_state2), - boost::bind(&std::map::value_type::second, _1)); + std::bind(&std::map::value_type::second, std::placeholders::_1)); rstate.setJointGroupPositions(jmg, ik_state2); rstate.update(); diff --git a/moveit_planners/pilz_industrial_motion_planner_testutils/src/xml_testdata_loader.cpp b/moveit_planners/pilz_industrial_motion_planner_testutils/src/xml_testdata_loader.cpp index 69054bc45d..38b5f4549b 100644 --- a/moveit_planners/pilz_industrial_motion_planner_testutils/src/xml_testdata_loader.cpp +++ b/moveit_planners/pilz_industrial_motion_planner_testutils/src/xml_testdata_loader.cpp @@ -141,27 +141,27 @@ XmlTestdataLoader::XmlTestdataLoader(const std::string& path_filename) : Testdat pt::read_xml(path_filename_, tree_, pt::xml_parser::no_comments); using std::placeholders::_1; - cmd_getter_funcs_["ptp"] = - AbstractCmdGetterUPtr(new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getPtpJoint, this, _1))); + cmd_getter_funcs_["ptp"] = AbstractCmdGetterUPtr( + new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getPtpJoint, this, std::placeholders::_1))); cmd_getter_funcs_["ptp_joint_cart"] = AbstractCmdGetterUPtr( - new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getPtpJointCart, this, _1))); - cmd_getter_funcs_["ptp_cart_cart"] = - AbstractCmdGetterUPtr(new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getPtpCart, this, _1))); - - cmd_getter_funcs_["lin"] = - AbstractCmdGetterUPtr(new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getLinJoint, this, _1))); - cmd_getter_funcs_["lin_cart"] = - AbstractCmdGetterUPtr(new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getLinCart, this, _1))); - - cmd_getter_funcs_["circ_center_cart"] = AbstractCmdGetterUPtr( - new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getCircCartCenterCart, this, _1))); - cmd_getter_funcs_["circ_interim_cart"] = AbstractCmdGetterUPtr( - new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getCircCartInterimCart, this, _1))); - cmd_getter_funcs_["circ_joint_interim_cart"] = AbstractCmdGetterUPtr( - new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getCircJointInterimCart, this, _1))); - - cmd_getter_funcs_["gripper"] = - AbstractCmdGetterUPtr(new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getGripper, this, _1))); + new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getPtpJointCart, this, std::placeholders::_1))); + cmd_getter_funcs_["ptp_cart_cart"] = AbstractCmdGetterUPtr( + new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getPtpCart, this, std::placeholders::_1))); + + cmd_getter_funcs_["lin"] = AbstractCmdGetterUPtr( + new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getLinJoint, this, std::placeholders::_1))); + cmd_getter_funcs_["lin_cart"] = AbstractCmdGetterUPtr( + new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getLinCart, this, std::placeholders::_1))); + + cmd_getter_funcs_["circ_center_cart"] = AbstractCmdGetterUPtr(new CmdGetterAdapter( + std::bind(&XmlTestdataLoader::getCircCartCenterCart, this, std::placeholders::_1))); + cmd_getter_funcs_["circ_interim_cart"] = AbstractCmdGetterUPtr(new CmdGetterAdapter( + std::bind(&XmlTestdataLoader::getCircCartInterimCart, this, std::placeholders::_1))); + cmd_getter_funcs_["circ_joint_interim_cart"] = AbstractCmdGetterUPtr(new CmdGetterAdapter( + std::bind(&XmlTestdataLoader::getCircJointInterimCart, this, std::placeholders::_1))); + + cmd_getter_funcs_["gripper"] = AbstractCmdGetterUPtr( + new CmdGetterAdapter(std::bind(&XmlTestdataLoader::getGripper, this, std::placeholders::_1))); } XmlTestdataLoader::XmlTestdataLoader(const std::string& path_filename, diff --git a/moveit_planners/sbpl/core/sbpl_interface/src/sbpl_meta_interface.cpp b/moveit_planners/sbpl/core/sbpl_interface/src/sbpl_meta_interface.cpp index 65e6dfef33..36debbe2af 100644 --- a/moveit_planners/sbpl/core/sbpl_interface/src/sbpl_meta_interface.cpp +++ b/moveit_planners/sbpl/core/sbpl_interface/src/sbpl_meta_interface.cpp @@ -57,10 +57,10 @@ bool SBPLMetaInterface::solve(const planning_scene::PlanningSceneConstPtr& plann PlanningParameters param_no_bfs; param_no_bfs.use_bfs_ = false; moveit_msgs::GetMotionPlan::Response res1, res2; - boost::thread thread1(boost::bind(&SBPLMetaInterface::runSolver, this, true, boost::cref(planning_scene), - boost::cref(req), boost::ref(res1), param_bfs)); - boost::thread thread2(boost::bind(&SBPLMetaInterface::runSolver, this, false, boost::cref(planning_scene), - boost::cref(req), boost::ref(res2), param_no_bfs)); + boost::thread thread1(std::bind(&SBPLMetaInterface::runSolver, this, true, boost::cref(planning_scene), + boost::cref(req), boost::ref(res1), param_bfs)); + boost::thread thread2(std::bind(&SBPLMetaInterface::runSolver, this, false, boost::cref(planning_scene), + boost::cref(req), boost::ref(res2), param_no_bfs)); boost::mutex::scoped_lock lock(planner_done_mutex_); planner_done_condition_.wait(lock); diff --git a/moveit_plugins/moveit_fake_controller_manager/src/moveit_fake_controllers.cpp b/moveit_plugins/moveit_fake_controller_manager/src/moveit_fake_controllers.cpp index 156142157e..50c09184a7 100644 --- a/moveit_plugins/moveit_fake_controller_manager/src/moveit_fake_controllers.cpp +++ b/moveit_plugins/moveit_fake_controller_manager/src/moveit_fake_controllers.cpp @@ -124,7 +124,7 @@ bool ThreadedController::sendTrajectory(const moveit_msgs::RobotTrajectory& t) cancelTrajectory(); // cancel any previous fake motion cancel_ = false; status_ = moveit_controller_manager::ExecutionStatus::PREEMPTED; - thread_ = boost::thread(boost::bind(&ThreadedController::execTrajectory, this, t)); + thread_ = boost::thread(std::bind(&ThreadedController::execTrajectory, this, t)); return true; } diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h index aae275a2e2..212992de5b 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -133,10 +133,11 @@ class GripperControllerHandle : public ActionBasedControllerHandlesendGoal(goal, - boost::bind(&GripperControllerHandle::controllerDoneCallback, this, _1, _2), - boost::bind(&GripperControllerHandle::controllerActiveCallback, this), - boost::bind(&GripperControllerHandle::controllerFeedbackCallback, this, _1)); + controller_action_client_->sendGoal( + goal, + std::bind(&GripperControllerHandle::controllerDoneCallback, this, std::placeholders::_1, std::placeholders::_2), + std::bind(&GripperControllerHandle::controllerActiveCallback, this), + std::bind(&GripperControllerHandle::controllerFeedbackCallback, this, std::placeholders::_1)); done_ = false; last_exec_ = moveit_controller_manager::ExecutionStatus::RUNNING; diff --git a/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp b/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp index d911ed6357..93eb3750a6 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp +++ b/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp @@ -62,10 +62,12 @@ bool FollowJointTrajectoryControllerHandle::sendTrajectory(const moveit_msgs::Ro control_msgs::FollowJointTrajectoryGoal goal = goal_template_; goal.trajectory = trajectory.joint_trajectory; - controller_action_client_->sendGoal( - goal, boost::bind(&FollowJointTrajectoryControllerHandle::controllerDoneCallback, this, _1, _2), - boost::bind(&FollowJointTrajectoryControllerHandle::controllerActiveCallback, this), - boost::bind(&FollowJointTrajectoryControllerHandle::controllerFeedbackCallback, this, _1)); + controller_action_client_->sendGoal(goal, + std::bind(&FollowJointTrajectoryControllerHandle::controllerDoneCallback, this, + std::placeholders::_1, std::placeholders::_2), + std::bind(&FollowJointTrajectoryControllerHandle::controllerActiveCallback, this), + std::bind(&FollowJointTrajectoryControllerHandle::controllerFeedbackCallback, + this, std::placeholders::_1)); done_ = false; last_exec_ = moveit_controller_manager::ExecutionStatus::RUNNING; return true; diff --git a/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp b/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp index 373e5e6b8b..9c6d88fc4f 100644 --- a/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp +++ b/moveit_ros/benchmarks/benchmarks/src/benchmark_execution.cpp @@ -1276,11 +1276,11 @@ void moveit_benchmarks::BenchmarkExecution::runGoalExistenceBenchmark(BenchmarkR // Compute IK ROS_INFO_STREAM("Processing goal " << req.motion_plan_request.goal_constraints[0].name << " ..."); ros::WallTime startTime = ros::WallTime::now(); - success = - robot_state.setFromIK(robot_state.getJointModelGroup(req.motion_plan_request.group_name), ik_pose, - req.motion_plan_request.num_planning_attempts, - req.motion_plan_request.allowed_planning_time, - boost::bind(&isIKSolutionCollisionFree, planning_scene_.get(), _1, _2, _3, &reachable)); + success = robot_state.setFromIK(robot_state.getJointModelGroup(req.motion_plan_request.group_name), ik_pose, + req.motion_plan_request.num_planning_attempts, + req.motion_plan_request.allowed_planning_time, + std::bind(&isIKSolutionCollisionFree, planning_scene_.get(), std::placeholders::_1, + std::placeholders::_2, std::placeholders::_3, &reachable)); if (success) { ROS_INFO(" Success!"); @@ -1370,7 +1370,8 @@ void moveit_benchmarks::BenchmarkExecution::runGoalExistenceBenchmark(BenchmarkR robot_state.setFromIK(robot_state.getJointModelGroup(req.motion_plan_request.group_name), ik_pose, req.motion_plan_request.num_planning_attempts, req.motion_plan_request.allowed_planning_time, - boost::bind(&isIKSolutionCollisionFree, planning_scene_.get(), _1, _2, _3, &reachable)); + std::bind(&isIKSolutionCollisionFree, planning_scene_.get(), std::placeholders::_1, + std::placeholders::_2, std::placeholders::_3, &reachable)); double duration = (ros::WallTime::now() - startTime).toSec(); if (success) diff --git a/moveit_ros/manipulation/move_group_pick_place_capability/src/pick_place_action_capability.cpp b/moveit_ros/manipulation/move_group_pick_place_capability/src/pick_place_action_capability.cpp index 21268b5b99..91796b7215 100644 --- a/moveit_ros/manipulation/move_group_pick_place_capability/src/pick_place_action_capability.cpp +++ b/moveit_ros/manipulation/move_group_pick_place_capability/src/pick_place_action_capability.cpp @@ -54,14 +54,16 @@ void move_group::MoveGroupPickPlaceAction::initialize() // start the pickup action server pickup_action_server_ = std::make_unique>( - root_node_handle_, PICKUP_ACTION, boost::bind(&MoveGroupPickPlaceAction::executePickupCallback, this, _1), false); - pickup_action_server_->registerPreemptCallback(boost::bind(&MoveGroupPickPlaceAction::preemptPickupCallback, this)); + root_node_handle_, PICKUP_ACTION, + std::bind(&MoveGroupPickPlaceAction::executePickupCallback, this, std::placeholders::_1), false); + pickup_action_server_->registerPreemptCallback(std::bind(&MoveGroupPickPlaceAction::preemptPickupCallback, this)); pickup_action_server_->start(); // start the place action server place_action_server_ = std::make_unique>( - root_node_handle_, PLACE_ACTION, boost::bind(&MoveGroupPickPlaceAction::executePlaceCallback, this, _1), false); - place_action_server_->registerPreemptCallback(boost::bind(&MoveGroupPickPlaceAction::preemptPlaceCallback, this)); + root_node_handle_, PLACE_ACTION, + std::bind(&MoveGroupPickPlaceAction::executePlaceCallback, this, std::placeholders::_1), false); + place_action_server_->registerPreemptCallback(std::bind(&MoveGroupPickPlaceAction::preemptPlaceCallback, this)); place_action_server_->start(); } @@ -259,17 +261,18 @@ void move_group::MoveGroupPickPlaceAction::executePickupCallbackPlanAndExecute( opt.replan_ = goal->planning_options.replan; opt.replan_attempts_ = goal->planning_options.replan_attempts; opt.replan_delay_ = goal->planning_options.replan_delay; - opt.before_execution_callback_ = boost::bind(&MoveGroupPickPlaceAction::startPickupExecutionCallback, this); + opt.before_execution_callback_ = std::bind(&MoveGroupPickPlaceAction::startPickupExecutionCallback, this); - opt.plan_callback_ = - boost::bind(&MoveGroupPickPlaceAction::planUsingPickPlacePickup, this, boost::cref(*goal), &action_res, _1); + opt.plan_callback_ = std::bind(&MoveGroupPickPlaceAction::planUsingPickPlacePickup, this, boost::cref(*goal), + &action_res, std::placeholders::_1); if (goal->planning_options.look_around && context_->plan_with_sensing_) { - opt.plan_callback_ = boost::bind(&plan_execution::PlanWithSensing::computePlan, context_->plan_with_sensing_.get(), - _1, opt.plan_callback_, goal->planning_options.look_around_attempts, - goal->planning_options.max_safe_execution_cost); + opt.plan_callback_ = + std::bind(&plan_execution::PlanWithSensing::computePlan, context_->plan_with_sensing_.get(), + std::placeholders::_1, opt.plan_callback_, goal->planning_options.look_around_attempts, + goal->planning_options.max_safe_execution_cost); context_->plan_with_sensing_->setBeforeLookCallback( - boost::bind(&MoveGroupPickPlaceAction::startPickupLookCallback, this)); + std::bind(&MoveGroupPickPlaceAction::startPickupLookCallback, this)); } plan_execution::ExecutableMotionPlan plan; @@ -290,16 +293,17 @@ void move_group::MoveGroupPickPlaceAction::executePlaceCallbackPlanAndExecute(co opt.replan_ = goal->planning_options.replan; opt.replan_attempts_ = goal->planning_options.replan_attempts; opt.replan_delay_ = goal->planning_options.replan_delay; - opt.before_execution_callback_ = boost::bind(&MoveGroupPickPlaceAction::startPlaceExecutionCallback, this); - opt.plan_callback_ = - boost::bind(&MoveGroupPickPlaceAction::planUsingPickPlacePlace, this, boost::cref(*goal), &action_res, _1); + opt.before_execution_callback_ = std::bind(&MoveGroupPickPlaceAction::startPlaceExecutionCallback, this); + opt.plan_callback_ = std::bind(&MoveGroupPickPlaceAction::planUsingPickPlacePlace, this, boost::cref(*goal), + &action_res, std::placeholders::_1); if (goal->planning_options.look_around && context_->plan_with_sensing_) { - opt.plan_callback_ = boost::bind(&plan_execution::PlanWithSensing::computePlan, context_->plan_with_sensing_.get(), - _1, opt.plan_callback_, goal->planning_options.look_around_attempts, - goal->planning_options.max_safe_execution_cost); + opt.plan_callback_ = + std::bind(&plan_execution::PlanWithSensing::computePlan, context_->plan_with_sensing_.get(), + std::placeholders::_1, opt.plan_callback_, goal->planning_options.look_around_attempts, + goal->planning_options.max_safe_execution_cost); context_->plan_with_sensing_->setBeforeLookCallback( - boost::bind(&MoveGroupPickPlaceAction::startPlaceLookCallback, this)); + std::bind(&MoveGroupPickPlaceAction::startPlaceLookCallback, this)); } plan_execution::ExecutableMotionPlan plan; diff --git a/moveit_ros/manipulation/pick_place/src/approach_and_translate_stage.cpp b/moveit_ros/manipulation/pick_place/src/approach_and_translate_stage.cpp index 4a667fd489..66b58f3119 100644 --- a/moveit_ros/manipulation/pick_place/src/approach_and_translate_stage.cpp +++ b/moveit_ros/manipulation/pick_place/src/approach_and_translate_stage.cpp @@ -181,7 +181,8 @@ void addGripperTrajectory(const ManipulationPlanPtr& plan, plan_execution::ExecutableTrajectory et(ee_closed_traj, name); // Add a callback to attach the object to the EE after closing the gripper - et.effect_on_success_ = boost::bind(&executeAttachObject, plan->shared_data_, plan->approach_posture_, _1); + et.effect_on_success_ = + std::bind(&executeAttachObject, plan->shared_data_, plan->approach_posture_, std::placeholders::_1); et.allowed_collision_matrix_ = collision_matrix; plan->trajectories_.push_back(et); } @@ -225,8 +226,8 @@ bool ApproachAndTranslateStage::evaluate(const ManipulationPlanPtr& plan) const // state validity checking during the approach must ensure that the gripper posture is that for pre-grasping moveit::core::GroupStateValidityCallbackFn approach_valid_callback = - boost::bind(&isStateCollisionFree, planning_scene_.get(), collision_matrix_.get(), verbose_, - &plan->approach_posture_, _1, _2, _3); + std::bind(&isStateCollisionFree, planning_scene_.get(), collision_matrix_.get(), verbose_, + &plan->approach_posture_, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); plan->goal_sampler_->setVerbose(verbose_); std::size_t attempted_possible_goal_states = 0; do // continously sample possible goal states @@ -276,8 +277,8 @@ bool ApproachAndTranslateStage::evaluate(const ManipulationPlanPtr& plan) const // state validity checking during the retreat after the grasp must ensure the gripper posture is that of the // actual grasp moveit::core::GroupStateValidityCallbackFn retreat_valid_callback = - boost::bind(&isStateCollisionFree, planning_scene_after_approach.get(), collision_matrix_.get(), verbose_, - &plan->retreat_posture_, _1, _2, _3); + std::bind(&isStateCollisionFree, planning_scene_after_approach.get(), collision_matrix_.get(), verbose_, + &plan->retreat_posture_, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3); // try to compute a straight line path that moves from the goal in a desired direction moveit::core::RobotStatePtr last_retreat_state( diff --git a/moveit_ros/manipulation/pick_place/src/manipulation_pipeline.cpp b/moveit_ros/manipulation/pick_place/src/manipulation_pipeline.cpp index 29cab837f5..b8512d5ab6 100644 --- a/moveit_ros/manipulation/pick_place/src/manipulation_pipeline.cpp +++ b/moveit_ros/manipulation/pick_place/src/manipulation_pipeline.cpp @@ -114,7 +114,7 @@ void ManipulationPipeline::start() stage->resetStopSignal(); for (std::size_t i = 0; i < processing_threads_.size(); ++i) if (!processing_threads_[i]) - processing_threads_[i] = new boost::thread(boost::bind(&ManipulationPipeline::processingThread, this, i)); + processing_threads_[i] = new boost::thread(std::bind(&ManipulationPipeline::processingThread, this, i)); } void ManipulationPipeline::signalStop() diff --git a/moveit_ros/manipulation/pick_place/src/pick_place.cpp b/moveit_ros/manipulation/pick_place/src/pick_place.cpp index 6b0b2eca8e..21d4bb87e2 100644 --- a/moveit_ros/manipulation/pick_place/src/pick_place.cpp +++ b/moveit_ros/manipulation/pick_place/src/pick_place.cpp @@ -51,8 +51,8 @@ const double PickPlace::DEFAULT_GRASP_POSTURE_COMPLETION_DURATION = 7.0; // sec PickPlacePlanBase::PickPlacePlanBase(const PickPlaceConstPtr& pick_place, const std::string& name) : pick_place_(pick_place), pipeline_(name, 4), last_plan_time_(0.0), done_(false) { - pipeline_.setSolutionCallback(boost::bind(&PickPlacePlanBase::foundSolution, this)); - pipeline_.setEmptyQueueCallback(boost::bind(&PickPlacePlanBase::emptyQueue, this)); + pipeline_.setSolutionCallback(std::bind(&PickPlacePlanBase::foundSolution, this)); + pipeline_.setEmptyQueueCallback(std::bind(&PickPlacePlanBase::emptyQueue, this)); } PickPlacePlanBase::~PickPlacePlanBase() = default; diff --git a/moveit_ros/manipulation/pick_place/src/pick_place_params.cpp b/moveit_ros/manipulation/pick_place/src/pick_place_params.cpp index addc270d44..7102d23715 100644 --- a/moveit_ros/manipulation/pick_place/src/pick_place_params.cpp +++ b/moveit_ros/manipulation/pick_place/src/pick_place_params.cpp @@ -49,8 +49,8 @@ class DynamicReconfigureImpl public: DynamicReconfigureImpl() : dynamic_reconfigure_server_(ros::NodeHandle("~/pick_place")) { - dynamic_reconfigure_server_.setCallback( - boost::bind(&DynamicReconfigureImpl::dynamicReconfigureCallback, this, _1, _2)); + dynamic_reconfigure_server_.setCallback(std::bind(&DynamicReconfigureImpl::dynamicReconfigureCallback, this, + std::placeholders::_1, std::placeholders::_2)); } const PickPlaceParams& getParams() const diff --git a/moveit_ros/manipulation/pick_place/src/reachable_valid_pose_filter.cpp b/moveit_ros/manipulation/pick_place/src/reachable_valid_pose_filter.cpp index 986c05602e..e30e58543c 100644 --- a/moveit_ros/manipulation/pick_place/src/reachable_valid_pose_filter.cpp +++ b/moveit_ros/manipulation/pick_place/src/reachable_valid_pose_filter.cpp @@ -37,7 +37,7 @@ #include #include #include -#include +#include #include pick_place::ReachableAndValidPoseFilter::ReachableAndValidPoseFilter( @@ -132,8 +132,9 @@ bool pick_place::ReachableAndValidPoseFilter::evaluate(const ManipulationPlanPtr constraints_sampler_manager_->selectSampler(planning_scene_, planning_group, plan->goal_constraints_); if (plan->goal_sampler_) { - plan->goal_sampler_->setGroupStateValidityCallback(boost::bind( - &isStateCollisionFree, planning_scene_.get(), collision_matrix_.get(), verbose_, plan.get(), _1, _2, _3)); + plan->goal_sampler_->setGroupStateValidityCallback( + std::bind(&isStateCollisionFree, planning_scene_.get(), collision_matrix_.get(), verbose_, plan.get(), + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); plan->goal_sampler_->setVerbose(verbose_); if (plan->goal_sampler_->sample(*token_state, plan->shared_data_->max_goal_sampling_attempts_)) { diff --git a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp index b281d8493d..ad8f373907 100644 --- a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp @@ -136,10 +136,11 @@ bool MoveGroupCartesianPathService::computeService(moveit_msgs::GetCartesianPath ls = std::make_unique(context_->planning_scene_monitor_); kset = std::make_unique((*ls)->getRobotModel()); kset->add(req.path_constraints, (*ls)->getTransforms()); - constraint_fn = boost::bind( + constraint_fn = std::bind( &isStateValid, req.avoid_collisions ? static_cast(*ls).get() : nullptr, - kset->empty() ? nullptr : kset.get(), _1, _2, _3); + kset->empty() ? nullptr : kset.get(), std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3); } bool global_frame = !moveit::core::Transforms::sameFrame(link_name, req.header.frame_id); ROS_INFO_NAMED(getName(), diff --git a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.cpp b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.cpp index 1003e8d0fe..cf7e900dbe 100644 --- a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.cpp @@ -52,9 +52,9 @@ void MoveGroupExecuteTrajectoryAction::initialize() // start the move action server execute_action_server_ = std::make_unique>( root_node_handle_, EXECUTE_ACTION_NAME, - boost::bind(&MoveGroupExecuteTrajectoryAction::executePathCallback, this, _1), false); + std::bind(&MoveGroupExecuteTrajectoryAction::executePathCallback, this, std::placeholders::_1), false); execute_action_server_->registerPreemptCallback( - boost::bind(&MoveGroupExecuteTrajectoryAction::preemptExecuteTrajectoryCallback, this)); + std::bind(&MoveGroupExecuteTrajectoryAction::preemptExecuteTrajectoryCallback, this)); execute_action_server_->start(); } diff --git a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_service_capability.cpp index 9e61129856..6da4e85e9e 100644 --- a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_service_capability.cpp @@ -60,7 +60,8 @@ void MoveGroupExecuteService::initialize() // Hence, we use our own asynchronous spinner listening to our own callback queue. ros::AdvertiseServiceOptions ops; ops.template init( - EXECUTE_SERVICE_NAME, boost::bind(&MoveGroupExecuteService::executeTrajectoryService, this, _1, _2)); + EXECUTE_SERVICE_NAME, std::bind(&MoveGroupExecuteService::executeTrajectoryService, this, std::placeholders::_1, + std::placeholders::_2)); ops.callback_queue = &callback_queue_; execute_service_ = root_node_handle_.advertiseService(ops); spinner_.start(); diff --git a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp index 78b03d2c31..279fc8aaa1 100644 --- a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp @@ -158,11 +158,12 @@ bool MoveGroupKinematicsService::computeIKService(moveit_msgs::GetPositionIK::Re moveit::core::RobotState rs = ls->getCurrentState(); kset.add(req.ik_request.constraints, ls->getTransforms()); computeIK(req.ik_request, res.solution, res.error_code, rs, - boost::bind(&isIKSolutionValid, - req.ik_request.avoid_collisions ? - static_cast(ls).get() : - nullptr, - kset.empty() ? nullptr : &kset, _1, _2, _3)); + std::bind(&isIKSolutionValid, + req.ik_request.avoid_collisions ? + static_cast(ls).get() : + nullptr, + kset.empty() ? nullptr : &kset, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3)); } else { diff --git a/moveit_ros/move_group/src/default_capabilities/move_action_capability.cpp b/moveit_ros/move_group/src/default_capabilities/move_action_capability.cpp index a6793cf255..4c353cd40d 100644 --- a/moveit_ros/move_group/src/default_capabilities/move_action_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/move_action_capability.cpp @@ -55,8 +55,9 @@ void MoveGroupMoveAction::initialize() { // start the move action server move_action_server_ = std::make_unique>( - root_node_handle_, MOVE_ACTION, boost::bind(&MoveGroupMoveAction::executeMoveCallback, this, _1), false); - move_action_server_->registerPreemptCallback(boost::bind(&MoveGroupMoveAction::preemptMoveCallback, this)); + root_node_handle_, MOVE_ACTION, std::bind(&MoveGroupMoveAction::executeMoveCallback, this, std::placeholders::_1), + false); + move_action_server_->registerPreemptCallback(std::bind(&MoveGroupMoveAction::preemptMoveCallback, this)); move_action_server_->start(); } @@ -132,16 +133,17 @@ void MoveGroupMoveAction::executeMoveCallbackPlanAndExecute(const moveit_msgs::M opt.replan_ = goal->planning_options.replan; opt.replan_attempts_ = goal->planning_options.replan_attempts; opt.replan_delay_ = goal->planning_options.replan_delay; - opt.before_execution_callback_ = boost::bind(&MoveGroupMoveAction::startMoveExecutionCallback, this); + opt.before_execution_callback_ = std::bind(&MoveGroupMoveAction::startMoveExecutionCallback, this); - opt.plan_callback_ = - boost::bind(&MoveGroupMoveAction::planUsingPlanningPipeline, this, boost::cref(motion_plan_request), _1); + opt.plan_callback_ = std::bind(&MoveGroupMoveAction::planUsingPlanningPipeline, this, + boost::cref(motion_plan_request), std::placeholders::_1); if (goal->planning_options.look_around && context_->plan_with_sensing_) { - opt.plan_callback_ = boost::bind(&plan_execution::PlanWithSensing::computePlan, context_->plan_with_sensing_.get(), - _1, opt.plan_callback_, goal->planning_options.look_around_attempts, - goal->planning_options.max_safe_execution_cost); - context_->plan_with_sensing_->setBeforeLookCallback(boost::bind(&MoveGroupMoveAction::startMoveLookCallback, this)); + opt.plan_callback_ = + std::bind(&plan_execution::PlanWithSensing::computePlan, context_->plan_with_sensing_.get(), + std::placeholders::_1, opt.plan_callback_, goal->planning_options.look_around_attempts, + goal->planning_options.max_safe_execution_cost); + context_->plan_with_sensing_->setBeforeLookCallback(std::bind(&MoveGroupMoveAction::startMoveLookCallback, this)); } plan_execution::ExecutableMotionPlan plan; diff --git a/moveit_ros/occupancy_map_monitor/src/occupancy_map_monitor.cpp b/moveit_ros/occupancy_map_monitor/src/occupancy_map_monitor.cpp index ed494f9f2d..390ab5db71 100644 --- a/moveit_ros/occupancy_map_monitor/src/occupancy_map_monitor.cpp +++ b/moveit_ros/occupancy_map_monitor/src/occupancy_map_monitor.cpp @@ -200,14 +200,17 @@ void OccupancyMapMonitor::addUpdater(const OccupancyMapUpdaterPtr& updater) // when we had one updater only, we passed direcly the transform cache callback to that updater if (map_updaters_.size() == 2) { - map_updaters_[0]->setTransformCacheCallback( - boost::bind(&OccupancyMapMonitor::getShapeTransformCache, this, 0, _1, _2, _3)); - map_updaters_[1]->setTransformCacheCallback( - boost::bind(&OccupancyMapMonitor::getShapeTransformCache, this, 1, _1, _2, _3)); + map_updaters_[0]->setTransformCacheCallback(std::bind(&OccupancyMapMonitor::getShapeTransformCache, this, 0, + std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3)); + map_updaters_[1]->setTransformCacheCallback(std::bind(&OccupancyMapMonitor::getShapeTransformCache, this, 1, + std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3)); } else - map_updaters_.back()->setTransformCacheCallback( - boost::bind(&OccupancyMapMonitor::getShapeTransformCache, this, map_updaters_.size() - 1, _1, _2, _3)); + map_updaters_.back()->setTransformCacheCallback(std::bind(&OccupancyMapMonitor::getShapeTransformCache, this, + map_updaters_.size() - 1, std::placeholders::_1, + std::placeholders::_2, std::placeholders::_3)); } else updater->setTransformCacheCallback(transform_cache_callback_); diff --git a/moveit_ros/occupancy_map_monitor/src/occupancy_map_server.cpp b/moveit_ros/occupancy_map_monitor/src/occupancy_map_server.cpp index b91b591d07..655d7916e3 100644 --- a/moveit_ros/occupancy_map_monitor/src/occupancy_map_server.cpp +++ b/moveit_ros/occupancy_map_monitor/src/occupancy_map_server.cpp @@ -72,7 +72,7 @@ int main(int argc, char** argv) std::shared_ptr buffer = std::make_shared(ros::Duration(5.0)); std::shared_ptr listener = std::make_shared(*buffer, nh); occupancy_map_monitor::OccupancyMapMonitor server(buffer); - server.setUpdateCallback(boost::bind(&publishOctomap, &octree_binary_pub, &server)); + server.setUpdateCallback(std::bind(&publishOctomap, &octree_binary_pub, &server)); server.startMonitor(); ros::spin(); diff --git a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp index c391989f90..3b5b907987 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp +++ b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp @@ -129,7 +129,8 @@ bool DepthImageOctomapUpdater::initialize() mesh_filter_->setShadowThreshold(shadow_threshold_); mesh_filter_->setPaddingOffset(padding_offset_); mesh_filter_->setPaddingScale(padding_scale_); - mesh_filter_->setTransformCallback(boost::bind(&DepthImageOctomapUpdater::getShapeTransform, this, _1, _2)); + mesh_filter_->setTransformCallback( + std::bind(&DepthImageOctomapUpdater::getShapeTransform, this, std::placeholders::_1, std::placeholders::_2)); return true; } diff --git a/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp b/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp index 7040e5fdeb..34e7e56923 100644 --- a/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp +++ b/moveit_ros/perception/lazy_free_space_updater/src/lazy_free_space_updater.cpp @@ -48,8 +48,8 @@ LazyFreeSpaceUpdater::LazyFreeSpaceUpdater(const collision_detection::OccMapTree , max_sensor_delta_(1e-3) // 1mm , process_occupied_cells_set_(nullptr) , process_model_cells_set_(nullptr) - , update_thread_(boost::bind(&LazyFreeSpaceUpdater::lazyUpdateThread, this)) - , process_thread_(boost::bind(&LazyFreeSpaceUpdater::processThread, this)) + , update_thread_(std::bind(&LazyFreeSpaceUpdater::lazyUpdateThread, this)) + , process_thread_(std::bind(&LazyFreeSpaceUpdater::processThread, this)) { } diff --git a/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp b/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp index acad8248c5..5bbe882391 100644 --- a/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp +++ b/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp @@ -91,7 +91,7 @@ void mesh_filter::DepthSelfFiltering::onInit() model_label_ptr_ = std::make_shared(); mesh_filter_ = std::make_shared>( - bind(&TransformProvider::getTransform, &transform_provider_, _1, _2), + bind(&TransformProvider::getTransform, &transform_provider_, std::placeholders::_1, std::placeholders::_2), mesh_filter::StereoCameraModel::REGISTERED_PSDK_PARAMS); mesh_filter_->parameters().setDepthRange(near_clipping_plane_distance_, far_clipping_plane_distance_); mesh_filter_->setShadowThreshold(shadow_threshold_); diff --git a/moveit_ros/perception/mesh_filter/test/mesh_filter_test.cpp b/moveit_ros/perception/mesh_filter/test/mesh_filter_test.cpp index 7ba637ba4f..c6ba027510 100644 --- a/moveit_ros/perception/mesh_filter/test/mesh_filter_test.cpp +++ b/moveit_ros/perception/mesh_filter/test/mesh_filter_test.cpp @@ -118,7 +118,8 @@ MeshFilterTest::MeshFilterTest(unsigned width, unsigned height, double nea , shadow_(shadow) , epsilon_(epsilon) , sensor_parameters_(width, height, near_, far_, width >> 1, height >> 1, width >> 1, height >> 1, 0.1, 0.1) - , filter_(std::bind(&MeshFilterTest::transformCallback, this, _1, _2), sensor_parameters_) + , filter_(std::bind(&MeshFilterTest::transformCallback, this, std::placeholders::_1, std::placeholders::_2), + sensor_parameters_) , sensor_data_(width_ * height_) , distance_(0.0) { diff --git a/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp b/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp index fb37bbf1a0..0295ace054 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp +++ b/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp @@ -99,7 +99,8 @@ bool PointCloudOctomapUpdater::initialize() tf_buffer_ = std::make_shared(); tf_listener_ = std::make_shared(*tf_buffer_, root_nh_); shape_mask_ = std::make_unique(); - shape_mask_->setTransformCallback(boost::bind(&PointCloudOctomapUpdater::getShapeTransform, this, _1, _2)); + shape_mask_->setTransformCallback( + std::bind(&PointCloudOctomapUpdater::getShapeTransform, this, std::placeholders::_1, std::placeholders::_2)); std::string prefix = ""; if (!ns_.empty()) @@ -120,13 +121,15 @@ void PointCloudOctomapUpdater::start() { point_cloud_filter_ = new tf2_ros::MessageFilter(*point_cloud_subscriber_, *tf_buffer_, monitor_->getMapFrame(), 5, root_nh_); - point_cloud_filter_->registerCallback(boost::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, _1)); + point_cloud_filter_->registerCallback( + std::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, std::placeholders::_1)); ROS_INFO_NAMED(LOGNAME, "Listening to '%s' using message filter with target frame '%s'", point_cloud_topic_.c_str(), point_cloud_filter_->getTargetFramesString().c_str()); } else { - point_cloud_subscriber_->registerCallback(boost::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, _1)); + point_cloud_subscriber_->registerCallback( + std::bind(&PointCloudOctomapUpdater::cloudMsgCallback, this, std::placeholders::_1)); ROS_INFO_NAMED(LOGNAME, "Listening to '%s'", point_cloud_topic_.c_str()); } } diff --git a/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp b/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp index eb01773539..2ec58d243a 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp +++ b/moveit_ros/planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp @@ -258,7 +258,7 @@ moveit::core::SolverAllocatorFn KinematicsPluginLoader::getLoaderFunction() moveit::tools::Profiler::ScopedBlock prof_block("KinematicsPluginLoader::getLoaderFunction"); if (loader_) - return boost::bind(&KinematicsLoaderImpl::allocKinematicsSolverWithCache, loader_.get(), _1); + return std::bind(&KinematicsLoaderImpl::allocKinematicsSolverWithCache, loader_.get(), std::placeholders::_1); rdf_loader::RDFLoader rml(robot_description_); robot_description_ = rml.getRobotDescription(); @@ -447,6 +447,7 @@ moveit::core::SolverAllocatorFn KinematicsPluginLoader::getLoaderFunction(const iksolver_to_tip_links); } - return boost::bind(&KinematicsPluginLoader::KinematicsLoaderImpl::allocKinematicsSolverWithCache, loader_.get(), _1); + return std::bind(&KinematicsPluginLoader::KinematicsLoaderImpl::allocKinematicsSolverWithCache, loader_.get(), + std::placeholders::_1); } } // namespace kinematics_plugin_loader diff --git a/moveit_ros/planning/plan_execution/src/plan_execution.cpp b/moveit_ros/planning/plan_execution/src/plan_execution.cpp index 577c5a02ba..aff65e3a98 100644 --- a/moveit_ros/planning/plan_execution/src/plan_execution.cpp +++ b/moveit_ros/planning/plan_execution/src/plan_execution.cpp @@ -54,8 +54,8 @@ class PlanExecution::DynamicReconfigureImpl DynamicReconfigureImpl(PlanExecution* owner) : owner_(owner), dynamic_reconfigure_server_(ros::NodeHandle("~/plan_execution")) { - dynamic_reconfigure_server_.setCallback( - boost::bind(&DynamicReconfigureImpl::dynamicReconfigureCallback, this, _1, _2)); + dynamic_reconfigure_server_.setCallback(std::bind(&DynamicReconfigureImpl::dynamicReconfigureCallback, this, + std::placeholders::_1, std::placeholders::_2)); } private: @@ -86,7 +86,8 @@ plan_execution::PlanExecution::PlanExecution( new_scene_update_ = false; // we want to be notified when new information is available - planning_scene_monitor_->addUpdateCallback(boost::bind(&PlanExecution::planningSceneUpdatedCallback, this, _1)); + planning_scene_monitor_->addUpdateCallback( + std::bind(&PlanExecution::planningSceneUpdatedCallback, this, std::placeholders::_1)); // start the dynamic-reconfigure server reconfigure_impl_ = new DynamicReconfigureImpl(this); @@ -404,9 +405,9 @@ moveit_msgs::MoveItErrorCodes plan_execution::PlanExecution::executeAndMonitor(E trajectory_monitor_->startTrajectoryMonitor(); // start a trajectory execution thread - trajectory_execution_manager_->execute(boost::bind(&PlanExecution::doneWithTrajectoryExecution, this, _1), - boost::bind(&PlanExecution::successfulTrajectorySegmentExecution, this, &plan, - _1)); + trajectory_execution_manager_->execute( + std::bind(&PlanExecution::doneWithTrajectoryExecution, this, std::placeholders::_1), + std::bind(&PlanExecution::successfulTrajectorySegmentExecution, this, &plan, std::placeholders::_1)); // wait for path to be done, while checking that the path does not become invalid ros::Rate r(100); path_became_invalid_ = false; diff --git a/moveit_ros/planning/plan_execution/src/plan_with_sensing.cpp b/moveit_ros/planning/plan_execution/src/plan_with_sensing.cpp index 9eb12255de..3b1cca9e7d 100644 --- a/moveit_ros/planning/plan_execution/src/plan_with_sensing.cpp +++ b/moveit_ros/planning/plan_execution/src/plan_with_sensing.cpp @@ -52,8 +52,8 @@ class PlanWithSensing::DynamicReconfigureImpl DynamicReconfigureImpl(PlanWithSensing* owner) : owner_(owner), dynamic_reconfigure_server_(ros::NodeHandle("~/sense_for_plan")) { - dynamic_reconfigure_server_.setCallback( - boost::bind(&DynamicReconfigureImpl::dynamicReconfigureCallback, this, _1, _2)); + dynamic_reconfigure_server_.setCallback(std::bind(&DynamicReconfigureImpl::dynamicReconfigureCallback, this, + std::placeholders::_1, std::placeholders::_2)); } private: diff --git a/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp b/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp index b8530d349e..fae2970a20 100644 --- a/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp +++ b/moveit_ros/planning/planning_components_tools/src/evaluate_collision_checking_speed.cpp @@ -118,7 +118,7 @@ int main(int argc, char** argv) for (unsigned int i = 0; i < states.size(); ++i) threads.push_back(new boost::thread( - boost::bind(&runCollisionDetection, i, trials, psm.getPlanningScene().get(), states[i].get()))); + std::bind(&runCollisionDetection, i, trials, psm.getPlanningScene().get(), states[i].get()))); for (unsigned int i = 0; i < states.size(); ++i) { diff --git a/moveit_ros/planning/planning_scene_monitor/src/current_state_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/current_state_monitor.cpp index 415906fef2..125dc1b983 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/current_state_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/current_state_monitor.cpp @@ -148,7 +148,7 @@ void CurrentStateMonitor::startStateMonitor(const std::string& joint_states_topi if (tf_buffer_ && !robot_model_->getMultiDOFJointModels().empty()) { tf_connection_ = std::make_shared( - tf_buffer_->_addTransformsChangedListener(boost::bind(&CurrentStateMonitor::tfCallback, this))); + tf_buffer_->_addTransformsChangedListener(std::bind(&CurrentStateMonitor::tfCallback, this))); } state_monitor_started_ = true; monitor_start_time_ = ros::Time::now(); diff --git a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp index f1edc7be71..773da3da8a 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp @@ -62,8 +62,8 @@ class PlanningSceneMonitor::DynamicReconfigureImpl DynamicReconfigureImpl(PlanningSceneMonitor* owner) : owner_(owner), dynamic_reconfigure_server_(ros::NodeHandle(decideNamespace(owner->getName()))) { - dynamic_reconfigure_server_.setCallback( - boost::bind(&DynamicReconfigureImpl::dynamicReconfigureCallback, this, _1, _2)); + dynamic_reconfigure_server_.setCallback(std::bind(&DynamicReconfigureImpl::dynamicReconfigureCallback, this, + std::placeholders::_1, std::placeholders::_2)); } private: @@ -223,10 +223,10 @@ void PlanningSceneMonitor::initialize(const planning_scene::PlanningScenePtr& sc { // The scene_ is loaded on the collision loader only if it was correctly instantiated collision_loader_.setupScene(nh_, scene_); - scene_->setAttachedBodyUpdateCallback( - boost::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, this, _1, _2)); - scene_->setCollisionObjectUpdateCallback( - boost::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, _1, _2)); + scene_->setAttachedBodyUpdateCallback(std::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, + this, std::placeholders::_1, std::placeholders::_2)); + scene_->setCollisionObjectUpdateCallback(std::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, + std::placeholders::_1, std::placeholders::_2)); } } else @@ -271,10 +271,10 @@ void PlanningSceneMonitor::monitorDiffs(bool flag) parent_scene_ = scene_; scene_ = parent_scene_->diff(); scene_const_ = scene_; - scene_->setAttachedBodyUpdateCallback( - boost::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, this, _1, _2)); - scene_->setCollisionObjectUpdateCallback( - boost::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, _1, _2)); + scene_->setAttachedBodyUpdateCallback(std::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, + this, std::placeholders::_1, std::placeholders::_2)); + scene_->setCollisionObjectUpdateCallback(std::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, + this, std::placeholders::_1, std::placeholders::_2)); } } else @@ -327,7 +327,7 @@ void PlanningSceneMonitor::startPublishingPlanningScene(SceneUpdateType update_t ROS_INFO_NAMED(LOGNAME, "Publishing maintained planning scene on '%s'", planning_scene_topic.c_str()); monitorDiffs(true); publish_planning_scene_ = - std::make_unique(boost::bind(&PlanningSceneMonitor::scenePublishingThread, this)); + std::make_unique(std::bind(&PlanningSceneMonitor::scenePublishingThread, this)); } } @@ -385,10 +385,10 @@ void PlanningSceneMonitor::scenePublishingThread() scene_->setCollisionObjectUpdateCallback(collision_detection::World::ObserverCallbackFn()); scene_->pushDiffs(parent_scene_); scene_->clearDiffs(); - scene_->setAttachedBodyUpdateCallback( - boost::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, this, _1, _2)); - scene_->setCollisionObjectUpdateCallback( - boost::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, _1, _2)); + scene_->setAttachedBodyUpdateCallback(std::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, + this, std::placeholders::_1, std::placeholders::_2)); + scene_->setCollisionObjectUpdateCallback(std::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, + this, std::placeholders::_1, std::placeholders::_2)); if (octomap_monitor_) { excludeAttachedBodiesFromOctree(); // in case updates have happened to the attached bodies, put them in @@ -593,10 +593,10 @@ bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::PlanningSc parent_scene_ = scene_; scene_ = parent_scene_->diff(); scene_const_ = scene_; - scene_->setAttachedBodyUpdateCallback( - boost::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, this, _1, _2)); - scene_->setCollisionObjectUpdateCallback( - boost::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, _1, _2)); + scene_->setAttachedBodyUpdateCallback(std::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, + this, std::placeholders::_1, std::placeholders::_2)); + scene_->setCollisionObjectUpdateCallback(std::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, + std::placeholders::_1, std::placeholders::_2)); } if (octomap_monitor_) { @@ -1097,9 +1097,10 @@ void PlanningSceneMonitor::startWorldGeometryMonitor(const std::string& collisio excludeAttachedBodiesFromOctree(); excludeWorldObjectsFromOctree(); - octomap_monitor_->setTransformCacheCallback( - boost::bind(&PlanningSceneMonitor::getShapeTransformCache, this, _1, _2, _3)); - octomap_monitor_->setUpdateCallback(boost::bind(&PlanningSceneMonitor::octomapUpdateCallback, this)); + octomap_monitor_->setTransformCacheCallback(std::bind(&PlanningSceneMonitor::getShapeTransformCache, this, + std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3)); + octomap_monitor_->setUpdateCallback(std::bind(&PlanningSceneMonitor::octomapUpdateCallback, this)); } octomap_monitor_->startMonitor(); } @@ -1129,7 +1130,8 @@ void PlanningSceneMonitor::startStateMonitor(const std::string& joint_states_top { if (!current_state_monitor_) current_state_monitor_ = std::make_shared(getRobotModel(), tf_buffer_, root_nh_); - current_state_monitor_->addUpdateCallback(boost::bind(&PlanningSceneMonitor::onStateUpdate, this, _1)); + current_state_monitor_->addUpdateCallback( + std::bind(&PlanningSceneMonitor::onStateUpdate, this, std::placeholders::_1)); current_state_monitor_->startStateMonitor(joint_states_topic); { diff --git a/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp index a6cea18d91..9449d1a573 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/trajectory_monitor.cpp @@ -77,7 +77,7 @@ void planning_scene_monitor::TrajectoryMonitor::startTrajectoryMonitor() { if (sampling_frequency_ > std::numeric_limits::epsilon() && !record_states_thread_) { - record_states_thread_ = std::make_unique(boost::bind(&TrajectoryMonitor::recordStates, this)); + record_states_thread_ = std::make_unique(std::bind(&TrajectoryMonitor::recordStates, this)); ROS_DEBUG_NAMED(LOGNAME, "Started trajectory monitor"); } } diff --git a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp index e5ef47bb5a..abe969aa11 100644 --- a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp +++ b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp @@ -60,8 +60,8 @@ class TrajectoryExecutionManager::DynamicReconfigureImpl DynamicReconfigureImpl(TrajectoryExecutionManager* owner) : owner_(owner), dynamic_reconfigure_server_(ros::NodeHandle("~/trajectory_execution")) { - dynamic_reconfigure_server_.setCallback( - boost::bind(&DynamicReconfigureImpl::dynamicReconfigureCallback, this, _1, _2)); + dynamic_reconfigure_server_.setCallback(std::bind(&DynamicReconfigureImpl::dynamicReconfigureCallback, this, + std::placeholders::_1, std::placeholders::_2)); } private: @@ -360,7 +360,7 @@ bool TrajectoryExecutionManager::pushAndExecute(const moveit_msgs::RobotTrajecto continuous_execution_queue_.push_back(context); if (!continuous_execution_thread_) continuous_execution_thread_ = - std::make_unique(boost::bind(&TrajectoryExecutionManager::continuousExecutionThread, this)); + std::make_unique(std::bind(&TrajectoryExecutionManager::continuousExecutionThread, this)); } last_execution_status_ = moveit_controller_manager::ExecutionStatus::SUCCEEDED; continuous_execution_condition_.notify_all(); diff --git a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp index c1ceab384b..81db35e044 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp @@ -1247,7 +1247,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl if (constraints_init_thread_) constraints_init_thread_->join(); constraints_init_thread_ = std::make_unique( - boost::bind(&MoveGroupInterfaceImpl::initializeConstraintsStorageThread, this, host, port)); + std::bind(&MoveGroupInterfaceImpl::initializeConstraintsStorageThread, this, host, port)); } void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz) diff --git a/moveit_ros/robot_interaction/src/interaction_handler.cpp b/moveit_ros/robot_interaction/src/interaction_handler.cpp index e26ccdc182..18868cb7c6 100644 --- a/moveit_ros/robot_interaction/src/interaction_handler.cpp +++ b/moveit_ros/robot_interaction/src/interaction_handler.cpp @@ -207,7 +207,7 @@ void InteractionHandler::handleGeneric(const GenericInteraction& g, StateChangeCallbackFn callback; // modify the RobotState in-place with the state_lock_ held. LockedRobotState::modifyState( - boost::bind(&InteractionHandler::updateStateGeneric, this, _1, &g, &feedback, &callback)); + std::bind(&InteractionHandler::updateStateGeneric, this, std::placeholders::_1, &g, &feedback, &callback)); // This calls update_callback_ to notify client that state changed. if (callback) @@ -238,8 +238,8 @@ void InteractionHandler::handleEndEffector(const EndEffectorInteraction& eef, // modify the RobotState in-place with state_lock_ held. // This locks state_lock_ before calling updateState() - LockedRobotState::modifyState( - boost::bind(&InteractionHandler::updateStateEndEffector, this, _1, &eef, &tpose.pose, &callback)); + LockedRobotState::modifyState(std::bind(&InteractionHandler::updateStateEndEffector, this, std::placeholders::_1, + &eef, &tpose.pose, &callback)); // This calls update_callback_ to notify client that state changed. if (callback) @@ -270,7 +270,7 @@ void InteractionHandler::handleJoint(const JointInteraction& vj, // modify the RobotState in-place with state_lock_ held. // This locks state_lock_ before calling updateState() LockedRobotState::modifyState( - boost::bind(&InteractionHandler::updateStateJoint, this, _1, &vj, &tpose.pose, &callback)); + std::bind(&InteractionHandler::updateStateJoint, this, std::placeholders::_1, &vj, &tpose.pose, &callback)); // This calls update_callback_ to notify client that state changed. if (callback) @@ -285,7 +285,7 @@ void InteractionHandler::updateStateGeneric(moveit::core::RobotState* state, con bool ok = g->process_feedback(*state, *feedback); bool error_state_changed = setErrorState(g->marker_name_suffix, !ok); if (update_callback_) - *callback = boost::bind(update_callback_, _1, error_state_changed); + *callback = std::bind(update_callback_, std::placeholders::_1, error_state_changed); } // MUST hold state_lock_ when calling this! @@ -299,7 +299,7 @@ void InteractionHandler::updateStateEndEffector(moveit::core::RobotState* state, bool ok = kinematic_options.setStateFromIK(*state, eef->parent_group, eef->parent_link, *pose); bool error_state_changed = setErrorState(eef->parent_group, !ok); if (update_callback_) - *callback = boost::bind(update_callback_, _1, error_state_changed); + *callback = std::bind(update_callback_, std::placeholders::_1, error_state_changed); } // MUST hold state_lock_ when calling this! @@ -316,7 +316,7 @@ void InteractionHandler::updateStateJoint(moveit::core::RobotState* state, const state->update(); if (update_callback_) - *callback = boost::bind(update_callback_, _1, false); + *callback = std::bind(update_callback_, std::placeholders::_1, false); } bool InteractionHandler::inError(const EndEffectorInteraction& eef) const diff --git a/moveit_ros/robot_interaction/src/robot_interaction.cpp b/moveit_ros/robot_interaction/src/robot_interaction.cpp index 2e555b5aec..d4128f0dc2 100644 --- a/moveit_ros/robot_interaction/src/robot_interaction.cpp +++ b/moveit_ros/robot_interaction/src/robot_interaction.cpp @@ -70,7 +70,7 @@ RobotInteraction::RobotInteraction(const moveit::core::RobotModelConstPtr& robot // spin a thread that will process feedback events run_processing_thread_ = true; - processing_thread_ = std::make_unique(boost::bind(&RobotInteraction::processingThread, this)); + processing_thread_ = std::make_unique(std::bind(&RobotInteraction::processingThread, this)); } RobotInteraction::~RobotInteraction() @@ -539,7 +539,8 @@ void RobotInteraction::addInteractiveMarkers(const InteractionHandlerPtr& handle for (const visualization_msgs::InteractiveMarker& im : ims) { int_marker_server_->insert(im); - int_marker_server_->setCallback(im.name, boost::bind(&RobotInteraction::processInteractiveMarkerFeedback, this, _1)); + int_marker_server_->setCallback(im.name, std::bind(&RobotInteraction::processInteractiveMarkerFeedback, this, + std::placeholders::_1)); // Add menu handler to all markers that this interaction handler creates. if (std::shared_ptr mh = handler->getMenuHandler()) @@ -569,7 +570,8 @@ void RobotInteraction::toggleMoveInteractiveMarkerTopic(bool enable) std::string topic_name = int_marker_move_topics_[i]; std::string marker_name = int_marker_names_[i]; int_marker_move_subscribers_.push_back(nh.subscribe( - topic_name, 1, boost::bind(&RobotInteraction::moveInteractiveMarker, this, marker_name, _1))); + topic_name, 1, + std::bind(&RobotInteraction::moveInteractiveMarker, this, marker_name, std::placeholders::_1))); } } } diff --git a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp index 8ff126b8c4..3e5b155768 100644 --- a/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp +++ b/moveit_ros/robot_interaction/test/locked_robot_state_test.cpp @@ -433,7 +433,7 @@ void MyInfo::modifyThreadFunc(robot_interaction::LockedRobotState* locked_state, { val += 0.0001; - locked_state->modifyState(boost::bind(&MyInfo::modifyFunc, this, _1, val)); + locked_state->modifyState(std::bind(&MyInfo::modifyFunc, this, std::placeholders::_1, val)); } cnt_lock_.lock(); diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp index b68d565d50..aa343aead9 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp @@ -174,7 +174,8 @@ MotionPlanningDisplay::MotionPlanningDisplay() trajectory_visual_ = std::make_shared(path_category_, this); // Start background jobs - background_process_.setJobUpdateEvent(boost::bind(&MotionPlanningDisplay::backgroundJobUpdate, this, _1, _2)); + background_process_.setJobUpdateEvent( + std::bind(&MotionPlanningDisplay::backgroundJobUpdate, this, std::placeholders::_1, std::placeholders::_2)); } // ****************************************************************************************** @@ -285,7 +286,7 @@ void MotionPlanningDisplay::toggleSelectPlanningGroupSubscription(bool enable) void MotionPlanningDisplay::selectPlanningGroupCallback(const std_msgs::StringConstPtr& msg) { // synchronize ROS callback with main loop - addMainLoopJob(boost::bind(&MotionPlanningDisplay::changePlanningGroup, this, msg->data)); + addMainLoopJob(std::bind(&MotionPlanningDisplay::changePlanningGroup, this, msg->data)); } void MotionPlanningDisplay::reset() @@ -324,7 +325,7 @@ void MotionPlanningDisplay::setName(const QString& name) void MotionPlanningDisplay::backgroundJobUpdate(moveit::tools::BackgroundProcessing::JobEvent /*unused*/, const std::string& /*unused*/) { - addMainLoopJob(boost::bind(&MotionPlanningDisplay::updateBackgroundJobProgressBar, this)); + addMainLoopJob(std::bind(&MotionPlanningDisplay::updateBackgroundJobProgressBar, this)); } void MotionPlanningDisplay::updateBackgroundJobProgressBar() @@ -722,7 +723,7 @@ void MotionPlanningDisplay::changedQueryStartState() setStatusTextColor(query_start_color_property_->getColor()); addStatusText("Changed start state"); drawQueryStartState(); - addBackgroundJob(boost::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, true), + addBackgroundJob(std::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, true), "publishInteractiveMarkers"); } @@ -733,7 +734,7 @@ void MotionPlanningDisplay::changedQueryGoalState() setStatusTextColor(query_goal_color_property_->getColor()); addStatusText("Changed goal state"); drawQueryGoalState(); - addBackgroundJob(boost::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, true), + addBackgroundJob(std::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, true), "publishInteractiveMarkers"); } @@ -806,7 +807,7 @@ void MotionPlanningDisplay::resetInteractiveMarkers() { query_start_state_->clearError(); query_goal_state_->clearError(); - addBackgroundJob(boost::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, false), + addBackgroundJob(std::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, false), "publishInteractiveMarkers"); } @@ -912,7 +913,7 @@ void MotionPlanningDisplay::scheduleDrawQueryStartState(robot_interaction::Inter { if (!planning_scene_monitor_) return; - addBackgroundJob(boost::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, !error_state_changed), + addBackgroundJob(std::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, !error_state_changed), "publishInteractiveMarkers"); updateQueryStartState(); } @@ -922,7 +923,7 @@ void MotionPlanningDisplay::scheduleDrawQueryGoalState(robot_interaction::Intera { if (!planning_scene_monitor_) return; - addBackgroundJob(boost::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, !error_state_changed), + addBackgroundJob(std::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, !error_state_changed), "publishInteractiveMarkers"); updateQueryGoalState(); } @@ -931,7 +932,7 @@ void MotionPlanningDisplay::updateQueryStartState() { queryStartStateChanged(); recomputeQueryStartStateMetrics(); - addMainLoopJob(boost::bind(&MotionPlanningDisplay::changedQueryStartState, this)); + addMainLoopJob(std::bind(&MotionPlanningDisplay::changedQueryStartState, this)); context_->queueRender(); } @@ -939,7 +940,7 @@ void MotionPlanningDisplay::updateQueryGoalState() { queryGoalStateChanged(); recomputeQueryGoalStateMetrics(); - addMainLoopJob(boost::bind(&MotionPlanningDisplay::changedQueryGoalState, this)); + addMainLoopJob(std::bind(&MotionPlanningDisplay::changedQueryGoalState, this)); context_->queueRender(); } @@ -1049,7 +1050,7 @@ void MotionPlanningDisplay::changedPlanningGroup() if (frame_) frame_->changePlanningGroup(); - addBackgroundJob(boost::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, false), + addBackgroundJob(std::bind(&MotionPlanningDisplay::publishInteractiveMarkers, this, false), "publishInteractiveMarkers"); } @@ -1119,7 +1120,7 @@ void MotionPlanningDisplay::populateMenuHandler(std::shared_ptrinsert(menu_states, state_name, - boost::bind(&MotionPlanningDisplay::setQueryStateHelper, this, is_start, state_name)); + std::bind(&MotionPlanningDisplay::setQueryStateHelper, this, is_start, state_name)); } // // Group commands, which end up being the same for both interaction handlers @@ -1127,7 +1128,7 @@ void MotionPlanningDisplay::populateMenuHandler(std::shared_ptrinsert("Planning Group", immh::FeedbackCallback()); // for (int i = 0; i < group_names.size(); ++i) // mh->insert(menu_groups, group_names[i], - // boost::bind(&MotionPlanningDisplay::changePlanningGroup, this, group_names[i])); + // std::bind(&MotionPlanningDisplay::changePlanningGroup, this, group_names[i])); } void MotionPlanningDisplay::onRobotModelLoaded() @@ -1138,7 +1139,8 @@ void MotionPlanningDisplay::onRobotModelLoaded() robot_interaction_ = std::make_shared(getRobotModel(), "rviz_moveit_motion_planning_display"); robot_interaction::KinematicOptions o; - o.state_validity_callback_ = boost::bind(&MotionPlanningDisplay::isIKSolutionCollisionFree, this, _1, _2, _3); + o.state_validity_callback_ = std::bind(&MotionPlanningDisplay::isIKSolutionCollisionFree, this, std::placeholders::_1, + std::placeholders::_2, std::placeholders::_3); robot_interaction_->getKinematicOptionsMap()->setOptions( robot_interaction::KinematicOptionsMap::ALL, o, robot_interaction::KinematicOptions::STATE_VALIDITY_CALLBACK); @@ -1153,8 +1155,10 @@ void MotionPlanningDisplay::onRobotModelLoaded() robot_interaction_, "start", *previous_state_, planning_scene_monitor_->getTFClient()); query_goal_state_ = std::make_shared( robot_interaction_, "goal", *previous_state_, planning_scene_monitor_->getTFClient()); - query_start_state_->setUpdateCallback(boost::bind(&MotionPlanningDisplay::scheduleDrawQueryStartState, this, _1, _2)); - query_goal_state_->setUpdateCallback(boost::bind(&MotionPlanningDisplay::scheduleDrawQueryGoalState, this, _1, _2)); + query_start_state_->setUpdateCallback(std::bind(&MotionPlanningDisplay::scheduleDrawQueryStartState, this, + std::placeholders::_1, std::placeholders::_2)); + query_goal_state_->setUpdateCallback(std::bind(&MotionPlanningDisplay::scheduleDrawQueryGoalState, this, + std::placeholders::_1, std::placeholders::_2)); // Interactive marker menus populateMenuHandler(menu_handler_start_); diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp index 8c627d9345..5775ea432f 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp @@ -34,6 +34,8 @@ /* Author: Ioan Sucan */ +#include + #include #include #include @@ -211,7 +213,7 @@ MotionPlanningFrame::MotionPlanningFrame(MotionPlanningDisplay* pdisplay, rviz:: semantic_world_.reset(); if (semantic_world_) { - semantic_world_->addTableCallback(boost::bind(&MotionPlanningFrame::updateTables, this)); + semantic_world_->addTableCallback(std::bind(&MotionPlanningFrame::updateTables, this)); } } catch (std::exception& ex) @@ -334,14 +336,13 @@ void MotionPlanningFrame::changePlanningGroupHelper() if (!planning_display_->getPlanningSceneMonitor()) return; - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::fillStateSelectionOptions, this)); - planning_display_->addMainLoopJob( - boost::bind(&MotionPlanningFrame::populateConstraintsList, this, std::vector())); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::fillStateSelectionOptions, this)); + planning_display_->addMainLoopJob([this]() { populateConstraintsList(std::vector()); }); const moveit::core::RobotModelConstPtr& robot_model = planning_display_->getRobotModel(); std::string group = planning_display_->getCurrentPlanningGroup(); planning_display_->addMainLoopJob( - boost::bind(&MotionPlanningParamWidget::setGroupName, ui_->planner_param_treeview, group)); + std::bind(&MotionPlanningParamWidget::setGroupName, ui_->planner_param_treeview, group)); planning_display_->addMainLoopJob( [=]() { ui_->planning_group_combo_box->setCurrentText(QString::fromStdString(group)); }); @@ -373,7 +374,7 @@ void MotionPlanningFrame::changePlanningGroupHelper() ROS_ERROR("%s", ex.what()); } planning_display_->addMainLoopJob( - boost::bind(&MotionPlanningParamWidget::setMoveGroup, ui_->planner_param_treeview, move_group_)); + std::bind(&MotionPlanningParamWidget::setMoveGroup, ui_->planner_param_treeview, move_group_)); if (move_group_) { move_group_->allowLooking(ui_->allow_looking->isChecked()); @@ -382,9 +383,8 @@ void MotionPlanningFrame::changePlanningGroupHelper() planning_display_->addMainLoopJob([=]() { ui_->use_cartesian_path->setEnabled(has_unique_endeffector); }); std::vector desc; if (move_group_->getInterfaceDescriptions(desc)) - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populatePlannersList, this, desc)); - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::populateConstraintsList, this), - "populateConstraintsList"); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::populatePlannersList, this, desc)); + planning_display_->addBackgroundJob([this]() { populateConstraintsList(); }, "populateConstraintsList"); if (first_time_) { @@ -399,7 +399,7 @@ void MotionPlanningFrame::changePlanningGroupHelper() planning_display_->useApproximateIK(ui_->approximate_ik->isChecked()); if (ui_->allow_external_program->isChecked()) planning_display_->addMainLoopJob( - boost::bind(&MotionPlanningFrame::allowExternalProgramCommunication, this, true)); + std::bind(&MotionPlanningFrame::allowExternalProgramCommunication, this, true)); } } } @@ -407,7 +407,7 @@ void MotionPlanningFrame::changePlanningGroupHelper() void MotionPlanningFrame::changePlanningGroup() { - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::changePlanningGroupHelper, this), + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::changePlanningGroupHelper, this), "Frame::changePlanningGroup"); joints_tab_->changePlanningGroup(planning_display_->getCurrentPlanningGroup(), planning_display_->getQueryStartStateHandler(), @@ -417,7 +417,7 @@ void MotionPlanningFrame::changePlanningGroup() void MotionPlanningFrame::sceneUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type) { if (update_type & planning_scene_monitor::PlanningSceneMonitor::UPDATE_GEOMETRY) - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populateCollisionObjectsList, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::populateCollisionObjectsList, this)); } void MotionPlanningFrame::addSceneObject() @@ -494,11 +494,11 @@ void MotionPlanningFrame::addSceneObject() } setLocalSceneEdited(); - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populateCollisionObjectsList, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::populateCollisionObjectsList, this)); // Automatically select the inserted object so that its IM is displayed planning_display_->addMainLoopJob( - boost::bind(&MotionPlanningFrame::setItemSelectionInList, this, shape_name, true, ui_->collision_objects_list)); + std::bind(&MotionPlanningFrame::setItemSelectionInList, this, shape_name, true, ui_->collision_objects_list)); planning_display_->queueRenderSceneGeometry(); } diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp index 358c8452da..f429794f02 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp @@ -53,7 +53,7 @@ namespace moveit_rviz_plugin { void MotionPlanningFrame::databaseConnectButtonClicked() { - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClicked, this), + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClicked, this), "connect to database"); } @@ -108,7 +108,7 @@ void MotionPlanningFrame::resetDbButtonClicked() return; planning_display_->addBackgroundJob( - boost::bind(&MotionPlanningFrame::computeResetDbButtonClicked, this, response.toStdString()), "reset database"); + std::bind(&MotionPlanningFrame::computeResetDbButtonClicked, this, response.toStdString()), "reset database"); } void MotionPlanningFrame::computeDatabaseConnectButtonClicked() @@ -119,12 +119,12 @@ void MotionPlanningFrame::computeDatabaseConnectButtonClicked() robot_state_storage_.reset(); constraints_storage_.reset(); planning_display_->addMainLoopJob( - boost::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 1)); + std::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 1)); } else { planning_display_->addMainLoopJob( - boost::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 2)); + std::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 2)); try { warehouse_ros::DatabaseConnection::Ptr conn = moveit_warehouse::loadDatabase(); @@ -138,19 +138,19 @@ void MotionPlanningFrame::computeDatabaseConnectButtonClicked() else { planning_display_->addMainLoopJob( - boost::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 3)); + std::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 3)); return; } } catch (std::exception& ex) { planning_display_->addMainLoopJob( - boost::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 3)); + std::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 3)); ROS_ERROR("%s", ex.what()); return; } planning_display_->addMainLoopJob( - boost::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 4)); + std::bind(&MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper, this, 4)); } } @@ -204,8 +204,7 @@ void MotionPlanningFrame::computeDatabaseConnectButtonClickedHelper(int mode) if (move_group_) { move_group_->setConstraintsDatabase(ui_->database_host->text().toStdString(), ui_->database_port->value()); - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::populateConstraintsList, this), - "populateConstraintsList"); + planning_display_->addBackgroundJob([this]() { populateConstraintsList(); }, "populateConstraintsList"); } } } diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_manipulation.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_manipulation.cpp index 76e4c0d6da..80ec560597 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_manipulation.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_manipulation.cpp @@ -59,11 +59,10 @@ void MotionPlanningFrame::detectObjectsButtonClicked() } if (semantic_world_) { - semantic_world_->addTableCallback(boost::bind(&MotionPlanningFrame::updateTables, this)); + semantic_world_->addTableCallback(std::bind(&MotionPlanningFrame::updateTables, this)); } } - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::triggerObjectDetection, this), - "detect objects"); + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::triggerObjectDetection, this), "detect objects"); } void MotionPlanningFrame::processDetectedObjects() @@ -167,7 +166,7 @@ void MotionPlanningFrame::triggerObjectDetection() void MotionPlanningFrame::listenDetectedObjects(const object_recognition_msgs::RecognizedObjectArrayPtr& /*msg*/) { ros::Duration(1.0).sleep(); - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::processDetectedObjects, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::processDetectedObjects, this)); } void MotionPlanningFrame::updateDetectedObjectsList(const std::vector& object_ids) @@ -197,13 +196,13 @@ void MotionPlanningFrame::updateDetectedObjectsList(const std::vectoraddBackgroundJob(boost::bind(&MotionPlanningFrame::publishTables, this), "publish tables"); + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::publishTables, this), "publish tables"); } void MotionPlanningFrame::publishTables() { semantic_world_->addTablesToCollisionWorld(); - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::updateSupportSurfacesList, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::updateSupportSurfacesList, this)); } void MotionPlanningFrame::selectedSupportSurfaceChanged() @@ -296,7 +295,7 @@ void MotionPlanningFrame::pickObjectButtonClicked() } ROS_INFO("Trying to pick up object %s from support surface %s", pick_object_name_[group_name].c_str(), support_surface_name_.c_str()); - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::pickObject, this), "pick"); + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::pickObject, this), "pick"); } void MotionPlanningFrame::placeObjectButtonClicked() @@ -342,7 +341,7 @@ void MotionPlanningFrame::placeObjectButtonClicked() upright_orientation, 0.1); planning_display_->visualizePlaceLocations(place_poses_); place_object_name_ = attached_bodies[0]->getName(); - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::placeObject, this), "place"); + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::placeObject, this), "place"); } void MotionPlanningFrame::pickObject() diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp index a196132170..d3a0e706dc 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp @@ -146,7 +146,7 @@ void MotionPlanningFrame::clearScene() ps->getPlanningSceneMsg(msg); planning_scene_publisher_.publish(msg); setLocalSceneEdited(false); - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populateCollisionObjectsList, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::populateCollisionObjectsList, this)); planning_display_->queueRenderSceneGeometry(); } } @@ -228,7 +228,7 @@ void MotionPlanningFrame::removeSceneObject() ps->getCurrentStateNonConst().clearAttachedBody(sel[i]->text().toStdString()); scene_marker_.reset(); setLocalSceneEdited(); - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populateCollisionObjectsList, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::populateCollisionObjectsList, this)); planning_display_->queueRenderSceneGeometry(); } } @@ -498,7 +498,7 @@ void MotionPlanningFrame::copySelectedCollisionObject() ROS_DEBUG("Copied collision object to '%s'", name.c_str()); } setLocalSceneEdited(); - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populateCollisionObjectsList, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::populateCollisionObjectsList, this)); } void MotionPlanningFrame::computeSaveSceneButtonClicked() @@ -517,7 +517,7 @@ void MotionPlanningFrame::computeSaveSceneButtonClicked() ROS_ERROR("%s", ex.what()); } - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populatePlanningSceneTreeView, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::populatePlanningSceneTreeView, this)); } } @@ -538,7 +538,7 @@ void MotionPlanningFrame::computeSaveQueryButtonClicked(const std::string& scene ROS_ERROR("%s", ex.what()); } - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populatePlanningSceneTreeView, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::populatePlanningSceneTreeView, this)); } } @@ -575,7 +575,7 @@ void MotionPlanningFrame::computeDeleteSceneButtonClicked() ROS_ERROR("%s", ex.what()); } } - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populatePlanningSceneTreeView, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::populatePlanningSceneTreeView, this)); } } } @@ -601,7 +601,7 @@ void MotionPlanningFrame::computeDeleteQueryButtonClicked() ROS_ERROR("%s", ex.what()); } planning_display_->addMainLoopJob( - boost::bind(&MotionPlanningFrame::computeDeleteQueryButtonClickedHelper, this, s)); + std::bind(&MotionPlanningFrame::computeDeleteQueryButtonClickedHelper, this, s)); } } } @@ -847,7 +847,7 @@ void MotionPlanningFrame::renameCollisionObject(QListWidgetItem* item) if (scene_marker_) { scene_marker_.reset(); - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::createSceneInteractiveMarker, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::createSceneInteractiveMarker, this)); } } } @@ -998,7 +998,7 @@ void MotionPlanningFrame::exportGeometryAsTextButtonClicked() QFileDialog::getSaveFileName(this, tr("Export Scene Geometry"), tr(""), tr("Scene Geometry (*.scene)")); if (!path.isEmpty()) planning_display_->addBackgroundJob( - boost::bind(&MotionPlanningFrame::computeExportGeometryAsText, this, path.toStdString()), "export as text"); + std::bind(&MotionPlanningFrame::computeExportGeometryAsText, this, path.toStdString()), "export as text"); } void MotionPlanningFrame::computeExportGeometryAsText(const std::string& path) @@ -1028,7 +1028,7 @@ void MotionPlanningFrame::computeImportGeometryFromText(const std::string& path) if (ps->loadGeometryFromStream(fin)) { ROS_INFO("Loaded scene geometry from '%s'", path.c_str()); - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populateCollisionObjectsList, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::populateCollisionObjectsList, this)); planning_display_->queueRenderSceneGeometry(); setLocalSceneEdited(); } @@ -1047,6 +1047,6 @@ void MotionPlanningFrame::importGeometryFromTextButtonClicked() QFileDialog::getOpenFileName(this, tr("Import Scene Geometry"), tr(""), tr("Scene Geometry (*.scene)")); if (!path.isEmpty()) planning_display_->addBackgroundJob( - boost::bind(&MotionPlanningFrame::computeImportGeometryFromText, this, path.toStdString()), "import from text"); + std::bind(&MotionPlanningFrame::computeImportGeometryFromText, this, path.toStdString()), "import from text"); } } // namespace moveit_rviz_plugin diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp index f5d116cbf2..c8767bef3a 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp @@ -53,15 +53,14 @@ namespace moveit_rviz_plugin void MotionPlanningFrame::planButtonClicked() { publishSceneIfNeeded(); - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computePlanButtonClicked, this), - "compute plan"); + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::computePlanButtonClicked, this), "compute plan"); } void MotionPlanningFrame::executeButtonClicked() { ui_->execute_button->setEnabled(false); // execution is done in a separate thread, to not block other background jobs by blocking for synchronous execution - planning_display_->spawnBackgroundJob(boost::bind(&MotionPlanningFrame::computeExecuteButtonClicked, this)); + planning_display_->spawnBackgroundJob(std::bind(&MotionPlanningFrame::computeExecuteButtonClicked, this)); } void MotionPlanningFrame::planAndExecuteButtonClicked() @@ -70,13 +69,13 @@ void MotionPlanningFrame::planAndExecuteButtonClicked() ui_->plan_and_execute_button->setEnabled(false); ui_->execute_button->setEnabled(false); // execution is done in a separate thread, to not block other background jobs by blocking for synchronous execution - planning_display_->spawnBackgroundJob(boost::bind(&MotionPlanningFrame::computePlanAndExecuteButtonClicked, this)); + planning_display_->spawnBackgroundJob(std::bind(&MotionPlanningFrame::computePlanAndExecuteButtonClicked, this)); } void MotionPlanningFrame::stopButtonClicked() { ui_->stop_button->setEnabled(false); // avoid clicking again - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeStopButtonClicked, this), "stop"); + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::computeStopButtonClicked, this), "stop"); } void MotionPlanningFrame::allowReplanningToggled(bool checked) @@ -269,8 +268,8 @@ void MotionPlanningFrame::onNewPlanningSceneState() void MotionPlanningFrame::startStateTextChanged(const QString& start_state) { // use background job: fetching the current state might take up to a second - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::startStateTextChangedExec, this, - start_state.toStdString()), + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::startStateTextChangedExec, this, + start_state.toStdString()), "update start state"); } @@ -285,7 +284,7 @@ void MotionPlanningFrame::goalStateTextChanged(const QString& goal_state) { // use background job: fetching the current state might take up to a second planning_display_->addBackgroundJob( - boost::bind(&MotionPlanningFrame::goalStateTextChangedExec, this, goal_state.toStdString()), "update goal state"); + std::bind(&MotionPlanningFrame::goalStateTextChangedExec, this, goal_state.toStdString()), "update goal state"); } void MotionPlanningFrame::goalStateTextChangedExec(const std::string& goal_state) @@ -454,8 +453,7 @@ void MotionPlanningFrame::populatePlannerDescription(const moveit_msgs::PlannerI void MotionPlanningFrame::populateConstraintsList() { if (move_group_) - planning_display_->addMainLoopJob( - boost::bind(&MotionPlanningFrame::populateConstraintsList, this, move_group_->getKnownConstraints())); + planning_display_->addMainLoopJob([this]() { populateConstraintsList(move_group_->getKnownConstraints()); }); } void MotionPlanningFrame::populateConstraintsList(const std::vector& constr) diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_scenes.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_scenes.cpp index 430e9cfbd3..b1c2e0849e 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_scenes.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_scenes.cpp @@ -108,7 +108,7 @@ void MotionPlanningFrame::saveSceneButtonClicked() } } - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeSaveSceneButtonClicked, this), + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::computeSaveSceneButtonClicked, this), "save scene"); } } @@ -132,7 +132,7 @@ void MotionPlanningFrame::saveQueryButtonClicked() { std::string scene = s->text(0).toStdString(); planning_display_->addBackgroundJob( - boost::bind(&MotionPlanningFrame::computeSaveQueryButtonClicked, this, scene, ""), "save query"); + std::bind(&MotionPlanningFrame::computeSaveQueryButtonClicked, this, scene, ""), "save query"); } else { @@ -177,7 +177,7 @@ void MotionPlanningFrame::saveQueryButtonClicked() } } planning_display_->addBackgroundJob( - boost::bind(&MotionPlanningFrame::computeSaveQueryButtonClicked, this, scene, query_name), "save query"); + std::bind(&MotionPlanningFrame::computeSaveQueryButtonClicked, this, scene, query_name), "save query"); } } } @@ -185,25 +185,25 @@ void MotionPlanningFrame::saveQueryButtonClicked() void MotionPlanningFrame::deleteSceneButtonClicked() { - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeDeleteSceneButtonClicked, this), + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::computeDeleteSceneButtonClicked, this), "delete scene"); } void MotionPlanningFrame::deleteQueryButtonClicked() { - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeDeleteQueryButtonClicked, this), + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::computeDeleteQueryButtonClicked, this), "delete query"); } void MotionPlanningFrame::loadSceneButtonClicked() { - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeLoadSceneButtonClicked, this), + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::computeLoadSceneButtonClicked, this), "load scene"); } void MotionPlanningFrame::loadQueryButtonClicked() { - planning_display_->addBackgroundJob(boost::bind(&MotionPlanningFrame::computeLoadQueryButtonClicked, this), + planning_display_->addBackgroundJob(std::bind(&MotionPlanningFrame::computeLoadQueryButtonClicked, this), "load query"); } @@ -221,7 +221,7 @@ void MotionPlanningFrame::warehouseItemNameChanged(QTreeWidgetItem* item, int co if (planning_scene_storage->hasPlanningScene(new_name)) { - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populatePlanningSceneTreeView, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::populatePlanningSceneTreeView, this)); QMessageBox::warning(this, "Scene not renamed", QString("The scene name '").append(item->text(column)).append("' already exists")); return; @@ -239,7 +239,7 @@ void MotionPlanningFrame::warehouseItemNameChanged(QTreeWidgetItem* item, int co std::string new_name = item->text(column).toStdString(); if (planning_scene_storage->hasPlanningQuery(scene, new_name)) { - planning_display_->addMainLoopJob(boost::bind(&MotionPlanningFrame::populatePlanningSceneTreeView, this)); + planning_display_->addMainLoopJob(std::bind(&MotionPlanningFrame::populatePlanningSceneTreeView, this)); QMessageBox::warning(this, "Query not renamed", QString("The query name '") .append(item->text(column)) diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp b/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp index bea40fafa0..cb9603c505 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp @@ -210,7 +210,7 @@ void PlanningSceneDisplay::reset() Display::reset(); if (isEnabled()) - addBackgroundJob(boost::bind(&PlanningSceneDisplay::loadRobotModel, this), "loadRobotModel"); + addBackgroundJob(std::bind(&PlanningSceneDisplay::loadRobotModel, this), "loadRobotModel"); if (planning_scene_robot_) { @@ -386,7 +386,7 @@ void PlanningSceneDisplay::changedPlanningSceneTopic() service_name = ros::names::append(getMoveGroupNS(), service_name); auto bg_func = [=]() { if (planning_scene_monitor_->requestPlanningSceneState(service_name)) - addMainLoopJob(boost::bind(&PlanningSceneDisplay::onNewPlanningSceneState, this)); + addMainLoopJob(std::bind(&PlanningSceneDisplay::onNewPlanningSceneState, this)); else setStatus(rviz::StatusProperty::Warn, "PlanningScene", "Requesting initial scene failed"); }; @@ -529,7 +529,7 @@ void PlanningSceneDisplay::loadRobotModel() // we need to make sure the clearing of the robot model is in the main thread, // so that rendering operations do not have data removed from underneath, // so the next function is executed in the main loop - addMainLoopJob(boost::bind(&PlanningSceneDisplay::clearRobotModel, this)); + addMainLoopJob(std::bind(&PlanningSceneDisplay::clearRobotModel, this)); waitForAllMainLoopJobs(); @@ -537,8 +537,9 @@ void PlanningSceneDisplay::loadRobotModel() if (psm->getPlanningScene()) { planning_scene_monitor_.swap(psm); - planning_scene_monitor_->addUpdateCallback(boost::bind(&PlanningSceneDisplay::sceneMonitorReceivedUpdate, this, _1)); - addMainLoopJob(boost::bind(&PlanningSceneDisplay::onRobotModelLoaded, this)); + planning_scene_monitor_->addUpdateCallback( + std::bind(&PlanningSceneDisplay::sceneMonitorReceivedUpdate, this, std::placeholders::_1)); + addMainLoopJob(std::bind(&PlanningSceneDisplay::onRobotModelLoaded, this)); waitForAllMainLoopJobs(); } else @@ -598,7 +599,7 @@ void PlanningSceneDisplay::onEnable() { Display::onEnable(); - addBackgroundJob(boost::bind(&PlanningSceneDisplay::loadRobotModel, this), "loadRobotModel"); + addBackgroundJob(std::bind(&PlanningSceneDisplay::loadRobotModel, this), "loadRobotModel"); if (planning_scene_robot_) { diff --git a/moveit_ros/warehouse/warehouse/src/save_to_warehouse.cpp b/moveit_ros/warehouse/warehouse/src/save_to_warehouse.cpp index 4b1afa32a3..b24612c183 100644 --- a/moveit_ros/warehouse/warehouse/src/save_to_warehouse.cpp +++ b/moveit_ros/warehouse/warehouse/src/save_to_warehouse.cpp @@ -186,14 +186,16 @@ int main(int argc, char** argv) ROS_INFO(" * %s", name.c_str()); } - psm.addUpdateCallback(boost::bind(&onSceneUpdate, &psm, &pss)); + psm.addUpdateCallback(std::bind(&onSceneUpdate, &psm, &pss)); boost::function callback1 = - boost::bind(&onMotionPlanRequest, _1, &psm, &pss); + std::bind(&onMotionPlanRequest, std::placeholders::_1, &psm, &pss); ros::Subscriber mplan_req_sub = nh.subscribe("motion_plan_request", 100, callback1); - boost::function callback2 = boost::bind(&onConstraints, _1, &cs); + boost::function callback2 = + std::bind(&onConstraints, std::placeholders::_1, &cs); ros::Subscriber constr_sub = nh.subscribe("constraints", 100, callback2); - boost::function callback3 = boost::bind(&onRobotState, _1, &rs); + boost::function callback3 = + std::bind(&onRobotState, std::placeholders::_1, &rs); ros::Subscriber state_sub = nh.subscribe("robot_state", 100, callback3); std::vector topics; diff --git a/moveit_ros/warehouse/warehouse/src/warehouse_services.cpp b/moveit_ros/warehouse/warehouse/src/warehouse_services.cpp index cc1614f668..2bf03d529c 100644 --- a/moveit_ros/warehouse/warehouse/src/warehouse_services.cpp +++ b/moveit_ros/warehouse/warehouse/src/warehouse_services.cpp @@ -181,27 +181,27 @@ int main(int argc, char** argv) boost::function - save_cb = boost::bind(&storeState, _1, _2, &rs); + save_cb = std::bind(&storeState, std::placeholders::_1, std::placeholders::_2, &rs); boost::function - list_cb = boost::bind(&listStates, _1, _2, &rs); + list_cb = std::bind(&listStates, std::placeholders::_1, std::placeholders::_2, &rs); boost::function - get_cb = boost::bind(&getState, _1, _2, &rs); + get_cb = std::bind(&getState, std::placeholders::_1, std::placeholders::_2, &rs); boost::function - has_cb = boost::bind(&hasState, _1, _2, &rs); + has_cb = std::bind(&hasState, std::placeholders::_1, std::placeholders::_2, &rs); boost::function - rename_cb = boost::bind(&renameState, _1, _2, &rs); + rename_cb = std::bind(&renameState, std::placeholders::_1, std::placeholders::_2, &rs); boost::function - delete_cb = boost::bind(&deleteState, _1, _2, &rs); + delete_cb = std::bind(&deleteState, std::placeholders::_1, std::placeholders::_2, &rs); ros::ServiceServer save_state_server = node.advertiseService("save_robot_state", save_cb); ros::ServiceServer list_states_server = node.advertiseService("list_robot_states", list_cb); diff --git a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp index 58421c7b40..ab57be15d4 100644 --- a/moveit_setup_assistant/src/tools/compute_default_collisions.cpp +++ b/moveit_setup_assistant/src/tools/compute_default_collisions.cpp @@ -564,7 +564,7 @@ unsigned int disableNeverInCollision(const unsigned int num_trials, planning_sce for (int i = 0; i < num_threads; ++i) { ThreadComputation tc(scene, req, i, num_trials / num_threads, &links_seen_colliding, &lock, progress); - bgroup.create_thread(boost::bind(&disableNeverInCollisionThread, tc)); + bgroup.create_thread(std::bind(&disableNeverInCollisionThread, tc)); } try diff --git a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp index 55458bbf89..2685d6d1d8 100644 --- a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp +++ b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp @@ -226,7 +226,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = file.file_name_; template_path = config_data_->appendPaths(config_data_->template_package_path_, "package.xml.template"); file.description_ = "Defines a ROS package"; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = MoveItConfigData::AUTHOR_INFO; gen_files_.push_back(file); @@ -235,7 +235,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = file.file_name_; template_path = config_data_->appendPaths(config_data_->template_package_path_, file.file_name_); file.description_ = "CMake build system configuration file"; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -249,7 +249,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = file.file_name_; file.description_ = "Folder containing all MoveIt configuration files for your robot. This folder is required and " "cannot be disabled."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::createFolder, this, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::createFolder, this, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -263,7 +263,7 @@ bool ConfigurationFilesWidget::loadGenFiles() "representation of semantic information about robots. This format is intended to represent " "information about the robot that is not in the URDF file, but it is useful for a variety of " "applications. The intention is to include information that has a semantic aspect to it."; - file.gen_func_ = boost::bind(&srdf::SRDFWriter::writeSRDF, config_data_->srdf_, _1); + file.gen_func_ = std::bind(&srdf::SRDFWriter::writeSRDF, config_data_->srdf_, std::placeholders::_1); file.write_on_changes = MoveItConfigData::SRDF; gen_files_.push_back(file); // special step required so the generated .setup_assistant yaml has this value @@ -280,7 +280,7 @@ bool ConfigurationFilesWidget::loadGenFiles() "planner_configs tag. While defining a planner configuration, the only mandatory parameter is " "'type', which is the name of the motion planner to be used. Any other planner-specific " "parameters can be defined but are optional."; - file.gen_func_ = boost::bind(&MoveItConfigData::outputOMPLPlanningYAML, config_data_, _1); + file.gen_func_ = std::bind(&MoveItConfigData::outputOMPLPlanningYAML, config_data_, std::placeholders::_1); file.write_on_changes = MoveItConfigData::GROUPS; gen_files_.push_back(file); @@ -288,7 +288,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.file_name_ = "chomp_planning.yaml"; file.rel_path_ = config_data_->appendPaths(config_path, file.file_name_); file.description_ = "Specifies which chomp planning plugin parameters to be used for the CHOMP planner"; - file.gen_func_ = boost::bind(&MoveItConfigData::outputCHOMPPlanningYAML, config_data_, _1); + file.gen_func_ = std::bind(&MoveItConfigData::outputCHOMPPlanningYAML, config_data_, std::placeholders::_1); file.write_on_changes = MoveItConfigData::GROUPS; // need to double check if this is actually correct! gen_files_.push_back(file); @@ -297,7 +297,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(config_path, file.file_name_); file.description_ = "Specifies which kinematic solver plugin to use for each planning group in the SRDF, as well as " "the kinematic solver search resolution."; - file.gen_func_ = boost::bind(&MoveItConfigData::outputKinematicsYAML, config_data_, _1); + file.gen_func_ = std::bind(&MoveItConfigData::outputKinematicsYAML, config_data_, std::placeholders::_1); file.write_on_changes = MoveItConfigData::GROUPS | MoveItConfigData::GROUP_KINEMATICS; gen_files_.push_back(file); @@ -309,7 +309,7 @@ bool ConfigurationFilesWidget::loadGenFiles() "and acceleration than those contained in your URDF. This information is used by our trajectory " "filtering system to assign reasonable velocities and timing for the trajectory before it is " "passed to the robots controllers."; - file.gen_func_ = boost::bind(&MoveItConfigData::outputJointLimitsYAML, config_data_, _1); + file.gen_func_ = std::bind(&MoveItConfigData::outputJointLimitsYAML, config_data_, std::placeholders::_1); file.write_on_changes = 0; // Can they be changed? gen_files_.push_back(file); @@ -320,7 +320,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.description_ = "Cartesian velocity for planning in the workspace." "The velocity is used by pilz industrial motion planner as maximum velocity for cartesian " "planning requests scaled by the velocity scaling factor of an individual planning request."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; // Can they be changed? gen_files_.push_back(file); @@ -329,7 +329,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(config_path, file.file_name_); file.description_ = "Creates dummy configurations for controllers that correspond to defined groups. This is mostly " "useful for testing."; - file.gen_func_ = boost::bind(&MoveItConfigData::outputFakeControllersYAML, config_data_, _1); + file.gen_func_ = std::bind(&MoveItConfigData::outputFakeControllersYAML, config_data_, std::placeholders::_1); file.write_on_changes = MoveItConfigData::GROUPS; gen_files_.push_back(file); @@ -337,7 +337,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.file_name_ = "simple_moveit_controllers.yaml"; file.rel_path_ = config_data_->appendPaths(config_path, file.file_name_); file.description_ = "Creates controller configuration for SimpleMoveItControllerManager"; - file.gen_func_ = boost::bind(&MoveItConfigData::outputSimpleControllersYAML, config_data_, _1); + file.gen_func_ = std::bind(&MoveItConfigData::outputSimpleControllersYAML, config_data_, std::placeholders::_1); file.write_on_changes = MoveItConfigData::GROUPS; gen_files_.push_back(file); @@ -346,14 +346,14 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(config_path, file.file_name_); template_path = config_data_->appendPaths(config_data_->template_package_path_, file.rel_path_); file.description_ = "Configuration of Gazebo controllers"; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); gen_files_.push_back(file); // ros_controllers.yaml -------------------------------------------------------------------------------------- file.file_name_ = "ros_controllers.yaml"; file.rel_path_ = config_data_->appendPaths(config_path, file.file_name_); file.description_ = "Creates controller configurations for ros_control."; - file.gen_func_ = boost::bind(&MoveItConfigData::outputROSControllersYAML, config_data_, _1); + file.gen_func_ = std::bind(&MoveItConfigData::outputROSControllersYAML, config_data_, std::placeholders::_1); file.write_on_changes = MoveItConfigData::GROUPS; gen_files_.push_back(file); @@ -361,7 +361,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.file_name_ = "sensors_3d.yaml"; file.rel_path_ = config_data_->appendPaths(config_path, file.file_name_); file.description_ = "Creates configurations 3d sensors."; - file.gen_func_ = boost::bind(&MoveItConfigData::output3DSensorPluginYAML, config_data_, _1); + file.gen_func_ = std::bind(&MoveItConfigData::output3DSensorPluginYAML, config_data_, std::placeholders::_1); file.write_on_changes = MoveItConfigData::SENSORS_CONFIG; gen_files_.push_back(file); @@ -376,7 +376,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = file.file_name_; file.description_ = "Folder containing all MoveIt launch files for your robot. " "This folder is required and cannot be disabled."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::createFolder, this, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::createFolder, this, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -387,7 +387,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.description_ = "Launches the move_group node that provides the MoveGroup action and other parameters MoveGroup action"; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -397,7 +397,7 @@ bool ConfigurationFilesWidget::loadGenFiles() template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Loads settings for the ROS parameter server, required for running MoveIt. This includes the " "SRDF, joints_limits.yaml file, ompl_planning.yaml file, optionally the URDF, etc"; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -407,7 +407,7 @@ bool ConfigurationFilesWidget::loadGenFiles() template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Visualize in Rviz the robot's planning groups running with interactive markers that allow goal " "states to be set."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -419,7 +419,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.description_ = "Intended to be included in other launch files that require the OMPL planning plugin. Defines " "the proper plugin name on the parameter server and a default selection of planning request " "adapters."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -431,7 +431,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.description_ = "Intended to be included in other launch files that require the Pilz industrial motion planner " "planning plugin. Defines the proper plugin name on the parameter server and a default selection " "of planning request adapters."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -443,7 +443,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.description_ = "Intended to be included in other launch files that require the CHOMP planning plugin. Defines " "the proper plugin name on the parameter server and a default selection of planning request " "adapters."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -452,7 +452,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Helper launch file that can choose between different planning pipelines to be loaded."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -461,7 +461,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Helper launch file that specifies default settings for MongoDB."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -470,7 +470,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Launch file for starting MongoDB."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -479,7 +479,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Launch file for starting the warehouse with a default MongoDB."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -488,7 +488,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Launch file for benchmarking OMPL planners"; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -497,7 +497,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Helper launch file that can choose between different sensor managers to be loaded."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -506,7 +506,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, "moveit_sensor_manager.launch.xml"); file.description_ = "Placeholder for settings specific to the MoveIt sensor manager implemented for you robot."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -516,7 +516,7 @@ bool ConfigurationFilesWidget::loadGenFiles() template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Loads settings for the ROS parameter server required for executing trajectories using the " "trajectory_execution_manager::TrajectoryExecutionManager."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -524,7 +524,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Loads the fake controller plugin."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -532,7 +532,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Loads the default controller plugin."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -540,7 +540,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Loads the ros_control controller plugin."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -549,7 +549,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Run a demo of MoveIt."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -558,7 +558,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Run a demo of MoveIt with Gazebo and Rviz"; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -568,7 +568,7 @@ bool ConfigurationFilesWidget::loadGenFiles() template_path = config_data_->appendPaths(template_launch_path, "gazebo.launch"); file.description_ = "Gazebo launch file which also launches ros_controllers and sends robot urdf to param server, " "then using gazebo_ros pkg the robot is spawned to Gazebo"; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); gen_files_.push_back(file); // joystick_control.launch ------------------------------------------------------------------ @@ -576,7 +576,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, file.file_name_); file.description_ = "Control the Rviz Motion Planning Plugin with a joystick"; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -588,7 +588,7 @@ bool ConfigurationFilesWidget::loadGenFiles() // up with the SA's real launch file file.description_ = "Launch file for easily re-starting the MoveIt Setup Assistant to edit this robot's generated " "configuration package."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -597,7 +597,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); template_path = config_data_->appendPaths(template_launch_path, "ros_controllers.launch"); file.description_ = "ros_controllers launch file"; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = MoveItConfigData::GROUPS; gen_files_.push_back(file); @@ -607,7 +607,7 @@ bool ConfigurationFilesWidget::loadGenFiles() template_path = config_data_->appendPaths(template_launch_path, "moveit.rviz"); file.description_ = "Configuration file for Rviz with the Motion Planning Plugin already setup. Used by passing " "roslaunch moveit_rviz.launch config:=true"; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1); file.write_on_changes = 0; gen_files_.push_back(file); @@ -619,7 +619,7 @@ bool ConfigurationFilesWidget::loadGenFiles() file.file_name_ = SETUP_ASSISTANT_FILE; file.rel_path_ = file.file_name_; file.description_ = "MoveIt Setup Assistant's hidden settings file. You should not need to edit this file."; - file.gen_func_ = boost::bind(&MoveItConfigData::outputSetupAssistantFile, config_data_, _1); + file.gen_func_ = std::bind(&MoveItConfigData::outputSetupAssistantFile, config_data_, std::placeholders::_1); file.write_on_changes = -1; // write on any changes gen_files_.push_back(file); diff --git a/moveit_setup_assistant/src/widgets/default_collisions_widget.cpp b/moveit_setup_assistant/src/widgets/default_collisions_widget.cpp index 76be30b8db..cb548414e4 100644 --- a/moveit_setup_assistant/src/widgets/default_collisions_widget.cpp +++ b/moveit_setup_assistant/src/widgets/default_collisions_widget.cpp @@ -235,7 +235,8 @@ void DefaultCollisionsWidget::startGeneratingCollisionTable() btn_revert_->setEnabled(true); // allow to interrupt and revert // create a MonitorThread running generateCollisionTable() in a worker thread and monitoring the progress - worker_ = new MonitorThread(boost::bind(&DefaultCollisionsWidget::generateCollisionTable, this, _1), progress_bar_); + worker_ = new MonitorThread(std::bind(&DefaultCollisionsWidget::generateCollisionTable, this, std::placeholders::_1), + progress_bar_); connect(worker_, SIGNAL(finished()), this, SLOT(finishGeneratingCollisionTable())); worker_->start(); // start after having finished() signal connected } @@ -820,7 +821,7 @@ moveit_setup_assistant::MonitorThread::MonitorThread(const boost::function