Skip to content

Commit 7f4b89e

Browse files
author
Simon Schmeisser
authored
Merge pull request #114 from jspricke/cleanup
Cleanup for new Ubuntu version
2 parents 91cecd2 + e2d1da4 commit 7f4b89e

File tree

3 files changed

+6
-6
lines changed

3 files changed

+6
-6
lines changed

CMakeLists.txt

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,6 @@
11
cmake_minimum_required(VERSION 3.0.2)
22
project(moveit_visual_tools)
33

4-
# C++ 11 required for OMPL
5-
add_compile_options(-std=c++11)
6-
74
# Load catkin and all dependencies required for this package
85
find_package(catkin REQUIRED COMPONENTS
96
rviz_visual_tools

src/imarker_end_effector.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -200,7 +200,8 @@ void IMarkerEndEffector::solveIK(Eigen::Isometry3d& pose)
200200
boost::scoped_ptr<planning_scene_monitor::LockedPlanningSceneRO> ls;
201201
ls.reset(new planning_scene_monitor::LockedPlanningSceneRO(psm_));
202202
constraint_fn = boost::bind(&isStateValid, static_cast<const planning_scene::PlanningSceneConstPtr&>(*ls).get(),
203-
collision_checking_verbose_, only_check_self_collision_, visual_tools_, _1, _2, _3);
203+
collision_checking_verbose_, only_check_self_collision_, visual_tools_,
204+
boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3);
204205
}
205206

206207
// Attempt to set robot to new pose
@@ -297,7 +298,8 @@ void IMarkerEndEffector::make6DofMarker(const geometry_msgs::Pose& pose)
297298
int_marker_.controls.push_back(control);
298299

299300
imarker_server_->insert(int_marker_);
300-
imarker_server_->setCallback(int_marker_.name, boost::bind(&IMarkerEndEffector::iMarkerCallback, this, _1));
301+
imarker_server_->setCallback(int_marker_.name,
302+
boost::bind(&IMarkerEndEffector::iMarkerCallback, this, boost::placeholders::_1));
301303
// menu_handler_.apply(*imarker_server_, int_marker_.name);
302304
}
303305

src/imarker_robot_state.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -355,7 +355,8 @@ bool IMarkerRobotState::setFromPoses(const EigenSTL::vector_Isometry3d& poses,
355355
boost::scoped_ptr<planning_scene_monitor::LockedPlanningSceneRO> ls;
356356
ls.reset(new planning_scene_monitor::LockedPlanningSceneRO(psm_));
357357
constraint_fn = boost::bind(&isIKStateValid, static_cast<const planning_scene::PlanningSceneConstPtr&>(*ls).get(),
358-
collision_checking_verbose_, only_check_self_collision_, visual_tools_, _1, _2, _3);
358+
collision_checking_verbose_, only_check_self_collision_, visual_tools_,
359+
boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3);
359360
#endif
360361

361362
// Solve

0 commit comments

Comments
 (0)