Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

small compilation fixes for macOS #271

Merged
merged 6 commits into from Sep 15, 2020
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
1 change: 1 addition & 0 deletions moveit_core/collision_detection_fcl/CMakeLists.txt
Expand Up @@ -30,6 +30,7 @@ ament_target_dependencies(collision_detector_fcl_plugin
)
target_link_libraries(collision_detector_fcl_plugin
${MOVEIT_LIB_NAME}
moveit_planning_scene
)

install(TARGETS ${MOVEIT_LIB_NAME} collision_detector_fcl_plugin
Expand Down
1 change: 1 addition & 0 deletions moveit_core/utils/CMakeLists.txt
Expand Up @@ -23,6 +23,7 @@ if(BUILD_TESTING)
add_library(${MOVEIT_TEST_LIB_NAME} SHARED src/robot_model_test_utils.cpp)
target_link_libraries(${MOVEIT_TEST_LIB_NAME} moveit_robot_model)
ament_target_dependencies(${MOVEIT_TEST_LIB_NAME}
ament_index_cpp
Boost
geometry_msgs
urdf
Expand Down
1 change: 1 addition & 0 deletions moveit_kinematics/kdl_kinematics_plugin/CMakeLists.txt
Expand Up @@ -12,6 +12,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
moveit_msgs
orocos_kdl
kdl_parser
tf2_kdl
EIGEN3
)

Expand Down
1 change: 1 addition & 0 deletions moveit_kinematics/lma_kinematics_plugin/CMakeLists.txt
Expand Up @@ -7,6 +7,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
rclcpp
moveit_core
moveit_msgs
tf2_kdl
)

install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION lib)
Expand Down
1 change: 1 addition & 0 deletions moveit_ros/move_group/CMakeLists.txt
Expand Up @@ -59,6 +59,7 @@ set_target_properties(moveit_move_group_default_capabilities
target_include_directories(moveit_move_group_default_capabilities PUBLIC include)
ament_target_dependencies(moveit_move_group_default_capabilities
rclcpp rclcpp_action moveit_core moveit_ros_planning std_srvs)
target_link_libraries(moveit_move_group_default_capabilities moveit_move_group_capabilities_base)

install(TARGETS move_group list_move_group_capabilities
RUNTIME
Expand Down
Expand Up @@ -149,7 +149,7 @@ bool MoveGroupCartesianPathService::computeService(
constraint_fn = boost::bind(
&isStateValid,
req->avoid_collisions ? static_cast<const planning_scene::PlanningSceneConstPtr&>(*ls).get() : nullptr,
kset->empty() ? nullptr : kset.get(), _1, _2, _3);
kset->empty() ? nullptr : kset.get(), boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

broader question: why are we using boost::bind instead of std::bind? Is there a lower-level library requiring it? If not, seems like we should update MoveIt2 to reduce our boost usage (core ROS2 has done so).

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

... or use lambda's.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The only downside to lambdas is that I'm not sure they are as broadly understood - they seem a little more "advanced". In various discussions I've recently had with ROS/ROS2 package maintainers, I've noticed there is pretty decent evidence that the more advanced the codebase, the harder it is to get community help.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I agree that we should switch to lambdas in cases where the function is trivial (i.e. log message and return of a result) or where another member function should be called but we need to preprocess the arguments. Otherwise,std::bind is often much shorter and more readable.

}
bool global_frame = !moveit::core::Transforms::sameFrame(link_name, req->header.frame_id);
RCLCPP_INFO(LOGGER, "Attempting to follow %u waypoints for link '%s' using a step of %lf m "
Expand Down
Expand Up @@ -167,7 +167,7 @@ bool MoveGroupKinematicsService::computeIKService(const std::shared_ptr<rmw_requ
boost::bind(&isIKSolutionValid, req->ik_request.avoid_collisions ?
static_cast<const planning_scene::PlanningSceneConstPtr&>(ls).get() :
nullptr,
kset.empty() ? nullptr : &kset, _1, _2, _3));
kset.empty() ? nullptr : &kset, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
}
else
{
Expand Down
Expand Up @@ -162,11 +162,11 @@ void MoveGroupMoveAction::executeMoveCallbackPlanAndExecute(const std::shared_pt
opt.before_execution_callback_ = boost::bind(&MoveGroupMoveAction::startMoveExecutionCallback, this);

opt.plan_callback_ =
boost::bind(&MoveGroupMoveAction::planUsingPlanningPipeline, this, boost::cref(motion_plan_request), _1);
boost::bind(&MoveGroupMoveAction::planUsingPlanningPipeline, this, boost::cref(motion_plan_request), boost::placeholders::_1);
if (goal->get_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->get_goal()->planning_options.look_around_attempts,
boost::placeholders::_1, opt.plan_callback_, goal->get_goal()->planning_options.look_around_attempts,
goal->get_goal()->planning_options.max_safe_execution_cost);
context_->plan_with_sensing_->setBeforeLookCallback(boost::bind(&MoveGroupMoveAction::startMoveLookCallback, this));
}
Expand Down
Expand Up @@ -260,7 +260,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 boost::bind(&KinematicsLoaderImpl::allocKinematicsSolverWithCache, loader_.get(), boost::placeholders::_1);

rdf_loader::RDFLoader rml(node_, robot_description_);
robot_description_ = rml.getRobotDescription();
Expand Down Expand Up @@ -417,6 +417,6 @@ moveit::core::SolverAllocatorFn KinematicsPluginLoader::getLoaderFunction(const
iksolver_to_tip_links));
}

return boost::bind(&KinematicsPluginLoader::KinematicsLoaderImpl::allocKinematicsSolverWithCache, loader_.get(), _1);
return boost::bind(&KinematicsPluginLoader::KinematicsLoaderImpl::allocKinematicsSolverWithCache, loader_.get(), boost::placeholders::_1);
}
} // namespace kinematics_plugin_loader
6 changes: 3 additions & 3 deletions moveit_ros/planning/plan_execution/src/plan_execution.cpp
Expand Up @@ -86,7 +86,7 @@ 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(boost::bind(&PlanExecution::planningSceneUpdatedCallback, this, boost::placeholders::_1));

// start the dynamic-reconfigure server
// reconfigure_impl_ = new DynamicReconfigureImpl(this);
Expand Down Expand Up @@ -402,8 +402,8 @@ moveit_msgs::msg::MoveItErrorCodes plan_execution::PlanExecution::executeAndMoni

// start a trajectory execution thread
trajectory_execution_manager_->execute(
boost::bind(&PlanExecution::doneWithTrajectoryExecution, this, _1),
boost::bind(&PlanExecution::successfulTrajectorySegmentExecution, this, &plan, _1));
boost::bind(&PlanExecution::doneWithTrajectoryExecution, this, boost::placeholders::_1),
boost::bind(&PlanExecution::successfulTrajectorySegmentExecution, this, &plan, boost::placeholders::_1));
// wait for path to be done, while checking that the path does not become invalid
rclcpp::WallRate r(100);
path_became_invalid_ = false;
Expand Down
1 change: 1 addition & 0 deletions moveit_ros/planning/planning_pipeline/CMakeLists.txt
Expand Up @@ -8,6 +8,7 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
moveit_msgs
rclcpp
Boost
pluginlib
)

install(TARGETS ${MOVEIT_LIB_NAME}
Expand Down
Expand Up @@ -184,9 +184,9 @@ void PlanningSceneMonitor::initialize(const planning_scene::PlanningScenePtr& sc
if (scene_)
{
scene_->setAttachedBodyUpdateCallback(
boost::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, this, _1, _2));
boost::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, this, boost::placeholders::_1, boost::placeholders::_2));
scene_->setCollisionObjectUpdateCallback(
boost::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, _1, _2));
boost::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, boost::placeholders::_1, boost::placeholders::_2));
}
}
else
Expand Down Expand Up @@ -322,9 +322,9 @@ void PlanningSceneMonitor::monitorDiffs(bool flag)
scene_ = parent_scene_->diff();
scene_const_ = scene_;
scene_->setAttachedBodyUpdateCallback(
boost::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, this, _1, _2));
boost::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, this, boost::placeholders::_1, boost::placeholders::_2));
scene_->setCollisionObjectUpdateCallback(
boost::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, _1, _2));
boost::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, boost::placeholders::_1, boost::placeholders::_2));
}
}
else
Expand Down Expand Up @@ -435,9 +435,9 @@ void PlanningSceneMonitor::scenePublishingThread()
scene_->pushDiffs(parent_scene_);
scene_->clearDiffs();
scene_->setAttachedBodyUpdateCallback(
boost::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, this, _1, _2));
boost::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, this, boost::placeholders::_1, boost::placeholders::_2));
scene_->setCollisionObjectUpdateCallback(
boost::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, _1, _2));
boost::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, boost::placeholders::_1, boost::placeholders::_2));
if (octomap_monitor_)
{
excludeAttachedBodiesFromOctree(); // in case updates have happened to the attached bodies, put them in
Expand Down Expand Up @@ -667,9 +667,9 @@ bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::msg::Plann
scene_ = parent_scene_->diff();
scene_const_ = scene_;
scene_->setAttachedBodyUpdateCallback(
boost::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, this, _1, _2));
boost::bind(&PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback, this, boost::placeholders::_1, boost::placeholders::_2));
scene_->setCollisionObjectUpdateCallback(
boost::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, _1, _2));
boost::bind(&PlanningSceneMonitor::currentWorldObjectUpdateCallback, this, boost::placeholders::_1, boost::placeholders::_2));
}
if (octomap_monitor_)
{
Expand Down Expand Up @@ -1174,7 +1174,7 @@ void PlanningSceneMonitor::startWorldGeometryMonitor(const std::string& collisio
excludeWorldObjectsFromOctree();

octomap_monitor_->setTransformCacheCallback(
boost::bind(&PlanningSceneMonitor::getShapeTransformCache, this, _1, _2, _3));
boost::bind(&PlanningSceneMonitor::getShapeTransformCache, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
octomap_monitor_->setUpdateCallback(boost::bind(&PlanningSceneMonitor::octomapUpdateCallback, this));
}
octomap_monitor_->startMonitor();
Expand Down Expand Up @@ -1207,7 +1207,7 @@ void PlanningSceneMonitor::startStateMonitor(const std::string& joint_states_top
{
current_state_monitor_.reset(new CurrentStateMonitor(pnode_, getRobotModel(), tf_buffer_));
}
current_state_monitor_->addUpdateCallback(boost::bind(&PlanningSceneMonitor::onStateUpdate, this, _1));
current_state_monitor_->addUpdateCallback(boost::bind(&PlanningSceneMonitor::onStateUpdate, this, boost::placeholders::_1));
current_state_monitor_->startStateMonitor(joint_states_topic);

{
Expand Down
13 changes: 7 additions & 6 deletions moveit_ros/robot_interaction/src/interaction_handler.cpp
@@ -1,3 +1,4 @@

/*********************************************************************
* Software License Agreement (BSD License)
*
Expand Down Expand Up @@ -210,7 +211,7 @@ void InteractionHandler::handleGeneric(
StateChangeCallbackFn callback;
// modify the RobotState in-place with the state_lock_ held.
LockedRobotState::modifyState(
boost::bind(&InteractionHandler::updateStateGeneric, this, _1, &g, &feedback, &callback));
boost::bind(&InteractionHandler::updateStateGeneric, this, boost::placeholders::_1, &g, &feedback, &callback));

// This calls update_callback_ to notify client that state changed.
if (callback)
Expand Down Expand Up @@ -243,7 +244,7 @@ void InteractionHandler::handleEndEffector(
// 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));
boost::bind(&InteractionHandler::updateStateEndEffector, this, boost::placeholders::_1, &eef, &tpose.pose, &callback));

// This calls update_callback_ to notify client that state changed.
if (callback)
Expand Down Expand Up @@ -274,7 +275,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));
boost::bind(&InteractionHandler::updateStateJoint, this, boost::placeholders::_1, &vj, &tpose.pose, &callback));

// This calls update_callback_ to notify client that state changed.
if (callback)
Expand All @@ -289,7 +290,7 @@ void InteractionHandler::updateStateGeneric(
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 = boost::bind(update_callback_, boost::placeholders::_1, error_state_changed);
}

// MUST hold state_lock_ when calling this!
Expand All @@ -303,7 +304,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 = boost::bind(update_callback_, boost::placeholders::_1, error_state_changed);
}

// MUST hold state_lock_ when calling this!
Expand All @@ -321,7 +322,7 @@ void InteractionHandler::updateStateJoint(moveit::core::RobotState* state, const
state->update();

if (update_callback_)
*callback = boost::bind(update_callback_, _1, false);
*callback = boost::bind(update_callback_, boost::placeholders::_1, false);
}

bool InteractionHandler::inError(const EndEffectorInteraction& eef) const
Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/robot_interaction/src/robot_interaction.cpp
Expand Up @@ -543,7 +543,7 @@ void RobotInteraction::addInteractiveMarkers(const InteractionHandlerPtr& handle
{
int_marker_server_->insert(im);
int_marker_server_->setCallback(im.name,
boost::bind(&RobotInteraction::processInteractiveMarkerFeedback, this, _1));
boost::bind(&RobotInteraction::processInteractiveMarkerFeedback, this, boost::placeholders::_1));

// Add menu handler to all markers that this interaction handler creates.
if (std::shared_ptr<interactive_markers::MenuHandler> mh = handler->getMenuHandler())
Expand Down
Expand Up @@ -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(boost::bind(&MyInfo::modifyFunc, this, boost::placeholders::_1, val));
}

cnt_lock_.lock();
Expand Down
2 changes: 2 additions & 0 deletions moveit_ros/visualization/CMakeLists.txt
Expand Up @@ -101,3 +101,5 @@ ament_export_dependencies(tf2_eigen)
ament_export_dependencies(Eigen3)
ament_export_dependencies(rviz_ogre_vendor)
ament_package()

include_directories("${OGRE_PREFIX_DIR}/include")
Expand Up @@ -13,14 +13,18 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}_core
moveit_msgs
pluginlib
Boost
rviz_ogre_vendor
)
target_include_directories(${MOVEIT_LIB_NAME}_core PRIVATE "${OGRE_PREFIX_DIR}/include")

add_library(${MOVEIT_LIB_NAME} SHARED src/plugin_init.cpp)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core Qt5::Widgets)
ament_target_dependencies(${MOVEIT_LIB_NAME}
pluginlib
rviz_ogre_vendor
)
target_include_directories(${MOVEIT_LIB_NAME} PRIVATE "${OGRE_PREFIX_DIR}/include")

install(DIRECTORY include/ DESTINATION include)

Expand Down
Expand Up @@ -542,7 +542,7 @@ void PlanningSceneDisplay::loadRobotModel()
{
planning_scene_monitor_.swap(psm);
planning_scene_monitor_->addUpdateCallback(
boost::bind(&PlanningSceneDisplay::sceneMonitorReceivedUpdate, this, _1));
boost::bind(&PlanningSceneDisplay::sceneMonitorReceivedUpdate, this, boost::placeholders::_1));
addMainLoopJob(boost::bind(&PlanningSceneDisplay::onRobotModelLoaded, this));
setStatus(rviz_common::properties::StatusProperty::Ok, "PlanningScene", "Planning Scene Loaded Successfully");
waitForAllMainLoopJobs();
Expand Down
Expand Up @@ -13,7 +13,9 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}_core
moveit_msgs
pluginlib
Boost
rviz_ogre_vendor
)
target_include_directories(${MOVEIT_LIB_NAME}_core PRIVATE "${OGRE_PREFIX_DIR}/include")

add_library(${MOVEIT_LIB_NAME} SHARED src/plugin_init.cpp)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
Expand All @@ -22,7 +24,9 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
rclcpp
pluginlib
Boost
rviz_ogre_vendor
)
target_include_directories(${MOVEIT_LIB_NAME} PRIVATE "${OGRE_PREFIX_DIR}/include")

install(DIRECTORY include/ DESTINATION include)

Expand Down
Expand Up @@ -37,7 +37,9 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
moveit_core
Boost
octomap_msgs
rviz_ogre_vendor
)
target_include_directories(${MOVEIT_LIB_NAME} PRIVATE "${OGRE_PREFIX_DIR}/include")

install(DIRECTORY include/ DESTINATION include)

Expand Down
Expand Up @@ -25,7 +25,9 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}_core
moveit_msgs
pluginlib
Boost
rviz_ogre_vendor
)
target_include_directories(${MOVEIT_LIB_NAME}_core PRIVATE "${OGRE_PREFIX_DIR}/include")

# Plugin Initializer
add_library(${MOVEIT_LIB_NAME} SHARED src/plugin_init.cpp)
Expand All @@ -35,7 +37,9 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
rclcpp
pluginlib
Boost
rviz_ogre_vendor
)
target_include_directories(${MOVEIT_LIB_NAME} PRIVATE "${OGRE_PREFIX_DIR}/include")

install(DIRECTORY include/ DESTINATION include)

Expand Down