Skip to content
Snippets Groups Projects
Commit 3cb210c9 authored by Johannes Mey's avatar Johannes Mey
Browse files

use updated simulation_util API

parent d18e1e64
No related branches found
No related tags found
No related merge requests found
......@@ -234,7 +234,7 @@ void addCollisionObjects(moveit::planning_interface::PlanningSceneInterface& pla
// the orientation is always the default
table1pose.orientation.w = 1;
GazeboZoneSpawner::spawnPrimitive("table1", table1, table1pose, 20, true);
GazeboZoneSpawner::spawnPrimitive("table1", table1, table1pose, std_msgs::ColorRGBA(), 20, true);
// END_SUB_TUTORIAL
collision_objects[0].operation = collision_objects[0].ADD;
......@@ -271,7 +271,7 @@ void addCollisionObjects(moveit::planning_interface::PlanningSceneInterface& pla
// the orientation is always the default
table2pose.orientation.w = 1;
GazeboZoneSpawner::spawnPrimitive("table2", table2, table2pose, 20, true);
GazeboZoneSpawner::spawnPrimitive("table2", table2, table2pose, std_msgs::ColorRGBA(), 20, true);
// END_SUB_TUTORIAL
collision_objects[1].operation = collision_objects[1].ADD;
......@@ -308,7 +308,7 @@ void addCollisionObjects(moveit::planning_interface::PlanningSceneInterface& pla
// the orientation is always the default
objectpose.orientation.w = 1;
GazeboZoneSpawner::spawnPrimitive("pickObject", object, objectpose, 1);
GazeboZoneSpawner::spawnPrimitive("pickObject", object, objectpose, std_msgs::ColorRGBA(), 1);
// END_SUB_TUTORIAL
collision_objects[2].operation = collision_objects[2].ADD;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment