diff --git a/.catkin_tools/profiles/default/devel_collisions.txt b/.catkin_tools/profiles/default/devel_collisions.txt index aa368eac912fc51e03fb4a4b2e9abdb298e11ec1..85e720efd862f0186b026050ac9089fe49892e14 100644 --- a/.catkin_tools/profiles/default/devel_collisions.txt +++ b/.catkin_tools/profiles/default/devel_collisions.txt @@ -1,4 +1,4 @@ /home/matteo/ws_panda/devel/./cmake.lock 42 -/home/matteo/reachability/devel/./cmake.lock 26279 +/home/matteo/reachability/devel/./cmake.lock 26292 /home/matteo/reachability/devel/lib/libmoveit_grasps.so 79 /home/matteo/reachability/devel/lib/libmoveit_grasps_filter.so 79 diff --git a/src/mtc/src/impl/moveit_mediator.cpp b/src/mtc/src/impl/moveit_mediator.cpp index 35d47b6b2305d1a3119760bbb560707ec3dd2e6d..6510241a217d208e1a6d57778c0f25f34eebc913 100644 --- a/src/mtc/src/impl/moveit_mediator.cpp +++ b/src/mtc/src/impl/moveit_mediator.cpp @@ -255,7 +255,7 @@ void Moveit_mediator::setup_task(){ } ROS_INFO("entry names"); for (auto den : ps1->allowed_collision_matrix.entry_names){ - ROS_INFO("%i", den.c_str()); + ROS_INFO("%s", den.c_str()); } ROS_INFO("entry values"); for (auto den : ps1->allowed_collision_matrix.entry_values){ @@ -325,7 +325,7 @@ void Moveit_mediator::setup_task(){ } ROS_INFO("entry names"); for (auto den : ps2->allowed_collision_matrix.entry_names){ - ROS_INFO("%i", den.c_str()); + ROS_INFO("%s", den.c_str()); } ROS_INFO("entry values"); for (auto den : ps2->allowed_collision_matrix.entry_values){ @@ -403,7 +403,7 @@ void Moveit_mediator::setup_task(){ } void Moveit_mediator::merge_ps(moveit_msgs::PlanningScene& origin, moveit_msgs::PlanningScene* merge, Moveit_robot* mr){ - + } void Moveit_mediator::parallel_exec(Moveit_robot& mr, moveit_msgs::RobotTrajectory rt, moveit_msgs::PlanningScene ps){