planning_scene_interface/src/planning_scene_interface.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Sachin Chitta */
36 
39 #include <moveit_msgs/GetPlanningScene.h>
40 #include <moveit_msgs/ApplyPlanningScene.h>
42 #include <ros/ros.h>
43 #include <algorithm>
44 
45 namespace moveit
46 {
47 namespace planning_interface
48 {
49 static const std::string LOGNAME = "planning_scene_interface";
50 
51 class PlanningSceneInterface::PlanningSceneInterfaceImpl
52 {
53 public:
54  explicit PlanningSceneInterfaceImpl(const std::string& ns = "", bool wait = true)
55  {
57  planning_scene_diff_publisher_ = node_handle_.advertise<moveit_msgs::PlanningScene>("planning_scene", 1);
62 
63  if (wait)
64  {
67  }
68  else
69  {
71  {
72  throw std::runtime_error("ROS services not available");
73  }
74  }
75  }
76 
77  std::vector<std::string> getKnownObjectNames(bool with_type)
78  {
79  moveit_msgs::GetPlanningScene::Request request;
80  moveit_msgs::GetPlanningScene::Response response;
81  std::vector<std::string> result;
82  request.components.components = request.components.WORLD_OBJECT_NAMES;
83  if (!planning_scene_service_.call(request, response))
84  return result;
85  if (with_type)
86  {
87  for (const moveit_msgs::CollisionObject& collision_object : response.scene.world.collision_objects)
88  if (!collision_object.type.key.empty())
89  result.push_back(collision_object.id);
90  }
91  else
92  {
93  for (const moveit_msgs::CollisionObject& collision_object : response.scene.world.collision_objects)
94  result.push_back(collision_object.id);
95  }
96  return result;
97  }
98 
99  std::vector<std::string> getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy,
100  double maxz, bool with_type, std::vector<std::string>& types)
101  {
102  moveit_msgs::GetPlanningScene::Request request;
103  moveit_msgs::GetPlanningScene::Response response;
104  std::vector<std::string> result;
105  request.components.components = request.components.WORLD_OBJECT_GEOMETRY;
106  if (!planning_scene_service_.call(request, response))
107  {
108  ROS_WARN_NAMED(LOGNAME, "Could not call planning scene service to get object names");
109  return result;
110  }
111 
112  for (const moveit_msgs::CollisionObject& collision_object : response.scene.world.collision_objects)
113  {
114  if (with_type && collision_object.type.key.empty())
115  continue;
116  if (collision_object.mesh_poses.empty() && collision_object.primitive_poses.empty())
117  continue;
118 
119  // Compose mesh and primitive poses with the object pose before checking inclusion in the ROI
120  geometry_msgs::Pose pose_tf;
121  geometry_msgs::TransformStamped tf;
122  tf.header = collision_object.header;
123  tf.transform.translation.x = collision_object.pose.position.x;
124  tf.transform.translation.y = collision_object.pose.position.y;
125  tf.transform.translation.z = collision_object.pose.position.z;
126  tf.transform.rotation.x = collision_object.pose.orientation.x;
127  tf.transform.rotation.y = collision_object.pose.orientation.y;
128  tf.transform.rotation.z = collision_object.pose.orientation.z;
129  tf.transform.rotation.w = collision_object.pose.orientation.w;
130 
131  bool good = true;
132  for (const geometry_msgs::Pose& mesh_pose : collision_object.mesh_poses)
133  {
134  tf2::doTransform(mesh_pose, pose_tf, tf);
135  if (!(pose_tf.position.x >= minx && pose_tf.position.x <= maxx && pose_tf.position.y >= miny &&
136  pose_tf.position.y <= maxy && pose_tf.position.z >= minz && pose_tf.position.z <= maxz))
137  {
138  good = false;
139  break;
140  }
141  }
142  for (const geometry_msgs::Pose& primitive_pose : collision_object.primitive_poses)
143  {
144  tf2::doTransform(primitive_pose, pose_tf, tf);
145  if (!(pose_tf.position.x >= minx && pose_tf.position.x <= maxx && pose_tf.position.y >= miny &&
146  pose_tf.position.y <= maxy && pose_tf.position.z >= minz && pose_tf.position.z <= maxz))
147  {
148  good = false;
149  break;
150  }
151  }
152  if (good)
153  {
154  result.push_back(collision_object.id);
155  if (with_type)
156  types.push_back(collision_object.type.key);
157  }
158  }
159  return result;
160  }
161 
162  std::map<std::string, geometry_msgs::Pose> getObjectPoses(const std::vector<std::string>& object_ids)
163  {
164  moveit_msgs::GetPlanningScene::Request request;
165  moveit_msgs::GetPlanningScene::Response response;
166  std::map<std::string, geometry_msgs::Pose> result;
167  request.components.components = request.components.WORLD_OBJECT_GEOMETRY;
168  if (!planning_scene_service_.call(request, response))
169  {
170  ROS_WARN_NAMED(LOGNAME, "Could not call planning scene service to get object names");
171  return result;
172  }
173 
174  for (const moveit_msgs::CollisionObject& collision_object : response.scene.world.collision_objects)
175  {
176  if (std::find(object_ids.begin(), object_ids.end(), collision_object.id) != object_ids.end())
177  {
178  result[collision_object.id] = collision_object.pose;
179  }
180  }
181  return result;
182  }
183 
184  std::map<std::string, moveit_msgs::CollisionObject> getObjects(const std::vector<std::string>& object_ids)
185  {
186  moveit_msgs::GetPlanningScene::Request request;
187  moveit_msgs::GetPlanningScene::Response response;
188  std::map<std::string, moveit_msgs::CollisionObject> result;
189  request.components.components = request.components.WORLD_OBJECT_GEOMETRY;
190  if (!planning_scene_service_.call(request, response))
191  {
192  ROS_WARN_NAMED(LOGNAME, "Could not call planning scene service to get object geometries");
193  return result;
194  }
195 
196  for (const moveit_msgs::CollisionObject& collision_object : response.scene.world.collision_objects)
197  {
198  if (object_ids.empty() || std::find(object_ids.begin(), object_ids.end(), collision_object.id) != object_ids.end())
199  {
200  result[collision_object.id] = collision_object;
201  }
202  }
203  return result;
204  }
205 
206  std::map<std::string, moveit_msgs::AttachedCollisionObject>
207  getAttachedObjects(const std::vector<std::string>& object_ids)
208  {
209  moveit_msgs::GetPlanningScene::Request request;
210  moveit_msgs::GetPlanningScene::Response response;
211  std::map<std::string, moveit_msgs::AttachedCollisionObject> result;
212  request.components.components = request.components.ROBOT_STATE_ATTACHED_OBJECTS;
213  if (!planning_scene_service_.call(request, response))
214  {
215  ROS_WARN_NAMED(LOGNAME, "Could not call planning scene service to get attached object geometries");
216  return result;
217  }
218 
219  for (const moveit_msgs::AttachedCollisionObject& attached_collision_object :
220  response.scene.robot_state.attached_collision_objects)
221  {
222  if (object_ids.empty() ||
223  std::find(object_ids.begin(), object_ids.end(), attached_collision_object.object.id) != object_ids.end())
224  {
225  result[attached_collision_object.object.id] = attached_collision_object;
226  }
227  }
228  return result;
229  }
230 
231  moveit_msgs::PlanningScene getPlanningSceneMsg(uint32_t components)
232  {
233  moveit_msgs::GetPlanningScene::Request request;
234  moveit_msgs::GetPlanningScene::Response response;
235  request.components.components = components;
236  if (!planning_scene_service_.call(request, response))
237  {
238  ROS_WARN_NAMED(LOGNAME, "Could not call planning scene service");
239  return moveit_msgs::PlanningScene();
240  }
241  return response.scene;
242  }
243 
244  bool applyPlanningScene(const moveit_msgs::PlanningScene& planning_scene)
245  {
246  moveit_msgs::ApplyPlanningScene::Request request;
247  moveit_msgs::ApplyPlanningScene::Response response;
248  request.scene = planning_scene;
249  if (!apply_planning_scene_service_.call(request, response))
250  {
251  ROS_WARN_NAMED(LOGNAME, "Failed to call ApplyPlanningScene service");
252  return false;
253  }
254  return response.success;
255  }
256 
257  void addCollisionObjects(const std::vector<moveit_msgs::CollisionObject>& collision_objects,
258  const std::vector<moveit_msgs::ObjectColor>& object_colors) const
259  {
260  moveit_msgs::PlanningScene planning_scene;
261  planning_scene.world.collision_objects = collision_objects;
262  planning_scene.object_colors = object_colors;
263 
264  for (size_t i = 0; i < planning_scene.object_colors.size(); ++i)
265  {
266  if (planning_scene.object_colors[i].id.empty() && i < collision_objects.size())
267  planning_scene.object_colors[i].id = collision_objects[i].id;
268  else
269  break;
270  }
271 
272  planning_scene.is_diff = true;
274  }
275 
276  void removeCollisionObjects(const std::vector<std::string>& object_ids) const
277  {
278  moveit_msgs::PlanningScene planning_scene;
279  moveit_msgs::CollisionObject object;
280  for (const std::string& object_id : object_ids)
281  {
282  object.id = object_id;
283  object.operation = object.REMOVE;
284  planning_scene.world.collision_objects.push_back(object);
285  }
286  planning_scene.is_diff = true;
288  }
289 
290  bool clear()
291  {
292  moveit_msgs::PlanningScene clear_scene;
293  clear_scene.is_diff = true;
294  clear_scene.robot_state.is_diff = true;
295  clear_scene.robot_state.attached_collision_objects.resize(1);
296  clear_scene.robot_state.attached_collision_objects[0].object.operation = moveit_msgs::CollisionObject::REMOVE;
297  clear_scene.world.collision_objects.resize(1);
298  clear_scene.world.collision_objects[0].operation = moveit_msgs::CollisionObject::REMOVE;
299 
300  return applyPlanningScene(clear_scene);
301  }
302 
303 private:
305  {
306  ros::Duration time_before_warning(5.0);
307  srv.waitForExistence(time_before_warning);
308  if (!srv.exists())
309  {
310  ROS_WARN_STREAM_NAMED(LOGNAME, "service '" << srv.getService() << "' not advertised yet. Continue waiting...");
311  srv.waitForExistence();
312  }
313  }
314 
319  moveit::core::RobotModelConstPtr robot_model_;
320 };
321 
322 PlanningSceneInterface::PlanningSceneInterface(const std::string& ns, bool wait)
323 {
325 }
326 
328 {
329  delete impl_;
330 }
331 
332 std::vector<std::string> PlanningSceneInterface::getKnownObjectNames(bool with_type)
333 {
334  return impl_->getKnownObjectNames(with_type);
335 }
336 
337 std::vector<std::string> PlanningSceneInterface::getKnownObjectNamesInROI(double minx, double miny, double minz,
338  double maxx, double maxy, double maxz,
339  bool with_type,
340  std::vector<std::string>& types)
341 {
342  return impl_->getKnownObjectNamesInROI(minx, miny, minz, maxx, maxy, maxz, with_type, types);
343 }
344 
345 std::map<std::string, geometry_msgs::Pose>
346 PlanningSceneInterface::getObjectPoses(const std::vector<std::string>& object_ids)
347 {
348  return impl_->getObjectPoses(object_ids);
349 }
350 
351 std::map<std::string, moveit_msgs::CollisionObject>
352 PlanningSceneInterface::getObjects(const std::vector<std::string>& object_ids)
353 {
354  return impl_->getObjects(object_ids);
355 }
356 
357 std::map<std::string, moveit_msgs::AttachedCollisionObject>
358 PlanningSceneInterface::getAttachedObjects(const std::vector<std::string>& object_ids)
359 {
360  return impl_->getAttachedObjects(object_ids);
361 }
362 
363 bool PlanningSceneInterface::applyCollisionObject(const moveit_msgs::CollisionObject& collision_object)
364 {
365  moveit_msgs::PlanningScene ps;
366  ps.robot_state.is_diff = true;
367  ps.is_diff = true;
368  ps.world.collision_objects.reserve(1);
369  ps.world.collision_objects.push_back(collision_object);
370  return applyPlanningScene(ps);
371 }
372 
373 bool PlanningSceneInterface::applyCollisionObject(const moveit_msgs::CollisionObject& collision_object,
374  const std_msgs::ColorRGBA& object_color)
375 {
376  moveit_msgs::PlanningScene ps;
377  ps.robot_state.is_diff = true;
378  ps.is_diff = true;
379  ps.world.collision_objects.reserve(1);
380  ps.world.collision_objects.push_back(collision_object);
381  moveit_msgs::ObjectColor oc;
382  oc.id = collision_object.id;
383  oc.color = object_color;
384  ps.object_colors.push_back(oc);
385  return applyPlanningScene(ps);
386 }
387 
388 bool PlanningSceneInterface::applyCollisionObjects(const std::vector<moveit_msgs::CollisionObject>& collision_objects,
389  const std::vector<moveit_msgs::ObjectColor>& object_colors)
390 {
391  moveit_msgs::PlanningScene ps;
392  ps.robot_state.is_diff = true;
393  ps.is_diff = true;
394  ps.world.collision_objects = collision_objects;
395  ps.object_colors = object_colors;
396 
397  for (size_t i = 0; i < ps.object_colors.size(); ++i)
398  {
399  if (ps.object_colors[i].id.empty() && i < collision_objects.size())
400  ps.object_colors[i].id = collision_objects[i].id;
401  else
402  break;
403  }
404 
405  return applyPlanningScene(ps);
406 }
407 
408 bool PlanningSceneInterface::applyAttachedCollisionObject(const moveit_msgs::AttachedCollisionObject& collision_object)
409 {
410  moveit_msgs::PlanningScene ps;
411  ps.robot_state.is_diff = true;
412  ps.is_diff = true;
413  ps.robot_state.attached_collision_objects.reserve(1);
414  ps.robot_state.attached_collision_objects.push_back(collision_object);
415  return applyPlanningScene(ps);
416 }
417 
419  const std::vector<moveit_msgs::AttachedCollisionObject>& collision_objects)
420 {
421  moveit_msgs::PlanningScene ps;
422  ps.robot_state.is_diff = true;
423  ps.is_diff = true;
424  ps.robot_state.attached_collision_objects = collision_objects;
425  return applyPlanningScene(ps);
426 }
427 
428 moveit_msgs::PlanningScene PlanningSceneInterface::getPlanningSceneMsg(uint32_t components)
429 {
430  return impl_->getPlanningSceneMsg(components);
431 }
432 
433 bool PlanningSceneInterface::applyPlanningScene(const moveit_msgs::PlanningScene& ps)
434 {
435  return impl_->applyPlanningScene(ps);
436 }
437 
438 void PlanningSceneInterface::addCollisionObjects(const std::vector<moveit_msgs::CollisionObject>& collision_objects,
439  const std::vector<moveit_msgs::ObjectColor>& object_colors) const
440 {
441  impl_->addCollisionObjects(collision_objects, object_colors);
442 }
443 
444 void PlanningSceneInterface::removeCollisionObjects(const std::vector<std::string>& object_ids) const
445 {
446  impl_->removeCollisionObjects(object_ids);
447 }
448 
450 {
451  return impl_->clear();
452 }
453 
454 } // namespace planning_interface
455 } // namespace moveit
response
const std::string response
move_group::GET_PLANNING_SCENE_SERVICE_NAME
static const std::string GET_PLANNING_SCENE_SERVICE_NAME
ros::ServiceClient::waitForExistence
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
move_group::APPLY_PLANNING_SCENE_SERVICE_NAME
static const std::string APPLY_PLANNING_SCENE_SERVICE_NAME
ros::Publisher
moveit::planning_interface::PlanningSceneInterface::applyAttachedCollisionObject
bool applyAttachedCollisionObject(const moveit_msgs::AttachedCollisionObject &attached_collision_object)
Apply attached collision object to the planning scene of the move_group node synchronously....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:472
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: planning_scene_interface/src/planning_scene_interface.cpp:383
ros::ServiceClient::exists
bool exists()
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::clear
bool clear()
Definition: planning_scene_interface/src/planning_scene_interface.cpp:354
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::PlanningSceneInterfaceImpl
PlanningSceneInterfaceImpl(const std::string &ns="", bool wait=true)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:118
ros.h
moveit::planning_interface::LOGNAME
const std::string LOGNAME
Definition: move_group_interface.cpp:148
moveit::planning_interface::PlanningSceneInterface::clear
bool clear()
Remove all the collision and attached objects from the world via the planning scene of the move_group...
Definition: planning_scene_interface/src/planning_scene_interface.cpp:513
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getKnownObjectNamesInROI
std::vector< std::string > getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz, bool with_type, std::vector< std::string > &types)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:163
moveit::planning_interface::PlanningSceneInterface::applyAttachedCollisionObjects
bool applyAttachedCollisionObjects(const std::vector< moveit_msgs::AttachedCollisionObject > &attached_collision_objects)
Apply attached collision objects to the planning scene of the move_group node synchronously....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:482
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::planning_scene_service_
ros::ServiceClient planning_scene_service_
Definition: planning_scene_interface/src/planning_scene_interface.cpp:380
moveit::planning_interface::PlanningSceneInterface::getKnownObjectNames
std::vector< std::string > getKnownObjectNames(bool with_type=false)
Get the names of all known objects in the world. If with_type is set to true, only return objects tha...
Definition: planning_scene_interface/src/planning_scene_interface.cpp:396
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::waitForService
void waitForService(ros::ServiceClient &srv)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:368
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::addCollisionObjects
void addCollisionObjects(const std::vector< moveit_msgs::CollisionObject > &collision_objects, const std::vector< moveit_msgs::ObjectColor > &object_colors) const
Definition: planning_scene_interface/src/planning_scene_interface.cpp:321
wait
void wait(int seconds)
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterface
PlanningSceneInterface(const std::string &ns="", bool wait=true)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:386
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
moveit::planning_interface::PlanningSceneInterface::applyPlanningScene
bool applyPlanningScene(const moveit_msgs::PlanningScene &ps)
Update the planning_scene of the move_group node with the given ps synchronously. Other PlanningScene...
Definition: planning_scene_interface/src/planning_scene_interface.cpp:497
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::removeCollisionObjects
void removeCollisionObjects(const std::vector< std::string > &object_ids) const
Definition: planning_scene_interface/src/planning_scene_interface.cpp:340
moveit::planning_interface::PlanningSceneInterface::getObjectPoses
std::map< std::string, geometry_msgs::Pose > getObjectPoses(const std::vector< std::string > &object_ids)
Get the poses from the objects identified by the given object ids list.
Definition: planning_scene_interface/src/planning_scene_interface.cpp:410
ros::ServiceClient::getService
std::string getService()
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl
Definition: planning_scene_interface/src/planning_scene_interface.cpp:115
capability_names.h
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getObjectPoses
std::map< std::string, geometry_msgs::Pose > getObjectPoses(const std::vector< std::string > &object_ids)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:226
moveit::planning_interface::PlanningSceneInterface::impl_
PlanningSceneInterfaceImpl * impl_
Definition: planning_scene_interface.h:221
moveit::planning_interface::PlanningSceneInterface::~PlanningSceneInterface
~PlanningSceneInterface()
Definition: planning_scene_interface/src/planning_scene_interface.cpp:391
ros::ServiceClient
moveit::planning_interface::PlanningSceneInterface::removeCollisionObjects
void removeCollisionObjects(const std::vector< std::string > &object_ids) const
Remove collision objects from the world via /planning_scene.
Definition: planning_scene_interface/src/planning_scene_interface.cpp:508
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getPlanningSceneMsg
moveit_msgs::PlanningScene getPlanningSceneMsg(uint32_t components)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:295
planning_scene_interface.h
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::planning_scene_diff_publisher_
ros::Publisher planning_scene_diff_publisher_
Definition: planning_scene_interface/src/planning_scene_interface.cpp:382
ROS_WARN_STREAM_NAMED
#define ROS_WARN_STREAM_NAMED(name, args)
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::node_handle_
ros::NodeHandle node_handle_
Definition: planning_scene_interface/src/planning_scene_interface.cpp:379
moveit
tf2::doTransform
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::applyPlanningScene
bool applyPlanningScene(const moveit_msgs::PlanningScene &planning_scene)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:308
moveit::planning_interface::PlanningSceneInterface::getObjects
std::map< std::string, moveit_msgs::CollisionObject > getObjects(const std::vector< std::string > &object_ids=std::vector< std::string >())
Get the objects identified by the given object ids list. If no ids are provided, return all the known...
Definition: planning_scene_interface/src/planning_scene_interface.cpp:416
moveit::planning_interface::PlanningSceneInterface::applyCollisionObjects
bool applyCollisionObjects(const std::vector< moveit_msgs::CollisionObject > &collision_objects, const std::vector< moveit_msgs::ObjectColor > &object_colors=std::vector< moveit_msgs::ObjectColor >())
Apply collision objects to the planning scene of the move_group node synchronously....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:452
planning_interface
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
tf2_geometry_msgs.h
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::apply_planning_scene_service_
ros::ServiceClient apply_planning_scene_service_
Definition: planning_scene_interface/src/planning_scene_interface.cpp:381
tf
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getObjects
std::map< std::string, moveit_msgs::CollisionObject > getObjects(const std::vector< std::string > &object_ids)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:248
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getKnownObjectNames
std::vector< std::string > getKnownObjectNames(bool with_type)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:141
planning_scene
moveit::planning_interface::PlanningSceneInterface::getAttachedObjects
std::map< std::string, moveit_msgs::AttachedCollisionObject > getAttachedObjects(const std::vector< std::string > &object_ids=std::vector< std::string >())
Get the attached objects identified by the given object ids list. If no ids are provided,...
Definition: planning_scene_interface/src/planning_scene_interface.cpp:422
ros::Duration
moveit::planning_interface::PlanningSceneInterface::applyCollisionObject
bool applyCollisionObject(const moveit_msgs::CollisionObject &collision_object)
Apply collision object to the planning scene of the move_group node synchronously....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:427
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getAttachedObjects
std::map< std::string, moveit_msgs::AttachedCollisionObject > getAttachedObjects(const std::vector< std::string > &object_ids)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:271
moveit::planning_interface::PlanningSceneInterface::addCollisionObjects
void addCollisionObjects(const std::vector< moveit_msgs::CollisionObject > &collision_objects, const std::vector< moveit_msgs::ObjectColor > &object_colors=std::vector< moveit_msgs::ObjectColor >()) const
Add collision objects to the world via /planning_scene. Make sure object.operation is set to object....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:502
ros::NodeHandle
moveit::planning_interface::PlanningSceneInterface::getKnownObjectNamesInROI
std::vector< std::string > getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz, bool with_type, std::vector< std::string > &types)
Get the names of known objects in the world that are located within a bounding region (specified in t...
Definition: planning_scene_interface/src/planning_scene_interface.cpp:401
moveit::planning_interface::PlanningSceneInterface::getPlanningSceneMsg
moveit_msgs::PlanningScene getPlanningSceneMsg(uint32_t components)
Get given components from move_group's PlanningScene.
Definition: planning_scene_interface/src/planning_scene_interface.cpp:492


planning_interface
Author(s): Ioan Sucan
autogenerated on Sat Apr 27 2024 02:27:01