39 #include <moveit_msgs/GetPlanningScene.h>
40 #include <moveit_msgs/ApplyPlanningScene.h>
48 static const std::string
LOGNAME =
"planning_scene_interface";
50 class PlanningSceneInterface::PlanningSceneInterfaceImpl
71 throw std::runtime_error(
"ROS services not available");
78 moveit_msgs::GetPlanningScene::Request request;
79 moveit_msgs::GetPlanningScene::Response
response;
80 std::vector<std::string> result;
81 request.components.components = request.components.WORLD_OBJECT_NAMES;
86 for (
const moveit_msgs::CollisionObject& collision_object :
response.scene.world.collision_objects)
87 if (!collision_object.type.key.empty())
88 result.push_back(collision_object.id);
92 for (
const moveit_msgs::CollisionObject& collision_object :
response.scene.world.collision_objects)
93 result.push_back(collision_object.id);
99 double maxz,
bool with_type, std::vector<std::string>& types)
101 moveit_msgs::GetPlanningScene::Request request;
102 moveit_msgs::GetPlanningScene::Response
response;
103 std::vector<std::string> result;
104 request.components.components = request.components.WORLD_OBJECT_GEOMETRY;
111 for (
const moveit_msgs::CollisionObject& collision_object :
response.scene.world.collision_objects)
113 if (with_type && collision_object.type.key.empty())
115 if (collision_object.mesh_poses.empty() && collision_object.primitive_poses.empty())
118 for (
const geometry_msgs::Pose& mesh_pose : collision_object.mesh_poses)
119 if (!(mesh_pose.position.x >= minx && mesh_pose.position.x <= maxx && mesh_pose.position.y >= miny &&
120 mesh_pose.position.y <= maxy && mesh_pose.position.z >= minz && mesh_pose.position.z <= maxz))
125 for (
const geometry_msgs::Pose& primitive_pose : collision_object.primitive_poses)
126 if (!(primitive_pose.position.x >= minx && primitive_pose.position.x <= maxx &&
127 primitive_pose.position.y >= miny && primitive_pose.position.y <= maxy &&
128 primitive_pose.position.z >= minz && primitive_pose.position.z <= maxz))
135 result.push_back(collision_object.id);
137 types.push_back(collision_object.type.key);
143 std::map<std::string, geometry_msgs::Pose>
getObjectPoses(
const std::vector<std::string>& object_ids)
145 moveit_msgs::GetPlanningScene::Request request;
146 moveit_msgs::GetPlanningScene::Response
response;
147 std::map<std::string, geometry_msgs::Pose> result;
148 request.components.components = request.components.WORLD_OBJECT_GEOMETRY;
155 for (
const moveit_msgs::CollisionObject& collision_object :
response.scene.world.collision_objects)
157 if (std::find(object_ids.begin(), object_ids.end(), collision_object.id) != object_ids.end())
159 if (collision_object.mesh_poses.empty() && collision_object.primitive_poses.empty())
161 if (!collision_object.mesh_poses.empty())
162 result[collision_object.id] = collision_object.mesh_poses[0];
164 result[collision_object.id] = collision_object.primitive_poses[0];
170 std::map<std::string, moveit_msgs::CollisionObject>
getObjects(
const std::vector<std::string>& object_ids)
172 moveit_msgs::GetPlanningScene::Request request;
173 moveit_msgs::GetPlanningScene::Response
response;
174 std::map<std::string, moveit_msgs::CollisionObject> result;
175 request.components.components = request.components.WORLD_OBJECT_GEOMETRY;
182 for (
const moveit_msgs::CollisionObject& collision_object :
response.scene.world.collision_objects)
184 if (object_ids.empty() || std::find(object_ids.begin(), object_ids.end(), collision_object.id) != object_ids.end())
186 result[collision_object.id] = collision_object;
192 std::map<std::string, moveit_msgs::AttachedCollisionObject>
195 moveit_msgs::GetPlanningScene::Request request;
196 moveit_msgs::GetPlanningScene::Response
response;
197 std::map<std::string, moveit_msgs::AttachedCollisionObject> result;
198 request.components.components = request.components.ROBOT_STATE_ATTACHED_OBJECTS;
205 for (
const moveit_msgs::AttachedCollisionObject& attached_collision_object :
206 response.scene.robot_state.attached_collision_objects)
208 if (object_ids.empty() ||
209 std::find(object_ids.begin(), object_ids.end(), attached_collision_object.object.id) != object_ids.end())
211 result[attached_collision_object.object.id] = attached_collision_object;
219 moveit_msgs::ApplyPlanningScene::Request request;
220 moveit_msgs::ApplyPlanningScene::Response
response;
230 void addCollisionObjects(
const std::vector<moveit_msgs::CollisionObject>& collision_objects,
231 const std::vector<moveit_msgs::ObjectColor>& object_colors)
const
239 if (
planning_scene.object_colors[i].id.empty() && i < collision_objects.size())
252 moveit_msgs::CollisionObject object;
253 for (
const std::string& object_id : object_ids)
255 object.id = object_id;
256 object.operation =
object.REMOVE;
298 double maxx,
double maxy,
double maxz,
300 std::vector<std::string>& types)
305 std::map<std::string, geometry_msgs::Pose>
311 std::map<std::string, moveit_msgs::CollisionObject>
317 std::map<std::string, moveit_msgs::AttachedCollisionObject>
325 moveit_msgs::PlanningScene ps;
326 ps.robot_state.is_diff =
true;
328 ps.world.collision_objects.reserve(1);
329 ps.world.collision_objects.push_back(collision_object);
334 const std_msgs::ColorRGBA& object_color)
336 moveit_msgs::PlanningScene ps;
337 ps.robot_state.is_diff =
true;
339 ps.world.collision_objects.reserve(1);
340 ps.world.collision_objects.push_back(collision_object);
341 moveit_msgs::ObjectColor oc;
342 oc.id = collision_object.id;
343 oc.color = object_color;
344 ps.object_colors.push_back(oc);
349 const std::vector<moveit_msgs::ObjectColor>& object_colors)
351 moveit_msgs::PlanningScene ps;
352 ps.robot_state.is_diff =
true;
354 ps.world.collision_objects = collision_objects;
355 ps.object_colors = object_colors;
357 for (
size_t i = 0; i < ps.object_colors.size(); ++i)
359 if (ps.object_colors[i].id.empty() && i < collision_objects.size())
360 ps.object_colors[i].id = collision_objects[i].id;
370 moveit_msgs::PlanningScene ps;
371 ps.robot_state.is_diff =
true;
373 ps.robot_state.attached_collision_objects.reserve(1);
374 ps.robot_state.attached_collision_objects.push_back(collision_object);
379 const std::vector<moveit_msgs::AttachedCollisionObject>& collision_objects)
381 moveit_msgs::PlanningScene ps;
382 ps.robot_state.is_diff =
true;
384 ps.robot_state.attached_collision_objects = collision_objects;
394 const std::vector<moveit_msgs::ObjectColor>& object_colors)
const