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, bool persistent_connections = false)
55  {
56  wait_ = wait;
57  persistent_connections_ = persistent_connections;
59  planning_scene_diff_publisher_ = node_handle_.advertise<moveit_msgs::PlanningScene>("planning_scene", 1);
60 
62  {
63  ROS_WARN_NAMED(LOGNAME, "To create persistent service clients, wait is set to true");
64  wait_ = true;
65  }
66 
69  }
70 
71  std::vector<std::string> getKnownObjectNames(bool with_type)
72  {
73  moveit_msgs::GetPlanningScene::Request request;
74  moveit_msgs::GetPlanningScene::Response response;
75  std::vector<std::string> result;
76  request.components.components = request.components.WORLD_OBJECT_NAMES;
77 
78  if (!getPlanningSceneServiceCall(request, response))
79  return result;
80  if (with_type)
81  {
82  for (const moveit_msgs::CollisionObject& collision_object : response.scene.world.collision_objects)
83  if (!collision_object.type.key.empty())
84  result.push_back(collision_object.id);
85  }
86  else
87  {
88  for (const moveit_msgs::CollisionObject& collision_object : response.scene.world.collision_objects)
89  result.push_back(collision_object.id);
90  }
91  return result;
92  }
93 
94  std::vector<std::string> getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy,
95  double maxz, bool with_type, std::vector<std::string>& types)
96  {
97  moveit_msgs::GetPlanningScene::Request request;
98  moveit_msgs::GetPlanningScene::Response response;
99  std::vector<std::string> result;
100  request.components.components = request.components.WORLD_OBJECT_GEOMETRY;
101 
102  if (!getPlanningSceneServiceCall(request, response))
103  {
104  ROS_WARN_NAMED(LOGNAME, "Could not call planning scene service to get object names");
105  return result;
106  }
107 
108  for (const moveit_msgs::CollisionObject& collision_object : response.scene.world.collision_objects)
109  {
110  if (with_type && collision_object.type.key.empty())
111  continue;
112  if (collision_object.mesh_poses.empty() && collision_object.primitive_poses.empty())
113  continue;
114 
115  // Compose mesh and primitive poses with the object pose before checking inclusion in the ROI
116  geometry_msgs::Pose pose_tf;
117  geometry_msgs::TransformStamped tf;
118  tf.header = collision_object.header;
119  tf.transform.translation.x = collision_object.pose.position.x;
120  tf.transform.translation.y = collision_object.pose.position.y;
121  tf.transform.translation.z = collision_object.pose.position.z;
122  tf.transform.rotation.x = collision_object.pose.orientation.x;
123  tf.transform.rotation.y = collision_object.pose.orientation.y;
124  tf.transform.rotation.z = collision_object.pose.orientation.z;
125  tf.transform.rotation.w = collision_object.pose.orientation.w;
126 
127  bool good = true;
128  for (const geometry_msgs::Pose& mesh_pose : collision_object.mesh_poses)
129  {
130  tf2::doTransform(mesh_pose, pose_tf, tf);
131  if (!(pose_tf.position.x >= minx && pose_tf.position.x <= maxx && pose_tf.position.y >= miny &&
132  pose_tf.position.y <= maxy && pose_tf.position.z >= minz && pose_tf.position.z <= maxz))
133  {
134  good = false;
135  break;
136  }
137  }
138  for (const geometry_msgs::Pose& primitive_pose : collision_object.primitive_poses)
139  {
140  tf2::doTransform(primitive_pose, pose_tf, tf);
141  if (!(pose_tf.position.x >= minx && pose_tf.position.x <= maxx && pose_tf.position.y >= miny &&
142  pose_tf.position.y <= maxy && pose_tf.position.z >= minz && pose_tf.position.z <= maxz))
143  {
144  good = false;
145  break;
146  }
147  }
148  if (good)
149  {
150  result.push_back(collision_object.id);
151  if (with_type)
152  types.push_back(collision_object.type.key);
153  }
154  }
155  return result;
156  }
157 
158  std::map<std::string, geometry_msgs::Pose> getObjectPoses(const std::vector<std::string>& object_ids)
159  {
160  moveit_msgs::GetPlanningScene::Request request;
161  moveit_msgs::GetPlanningScene::Response response;
162  std::map<std::string, geometry_msgs::Pose> result;
163  request.components.components = request.components.WORLD_OBJECT_GEOMETRY;
164 
165  if (!getPlanningSceneServiceCall(request, response))
166  {
167  ROS_WARN_NAMED(LOGNAME, "Could not call planning scene service to get object names");
168  return result;
169  }
170 
171  for (const moveit_msgs::CollisionObject& collision_object : response.scene.world.collision_objects)
172  {
173  if (std::find(object_ids.begin(), object_ids.end(), collision_object.id) != object_ids.end())
174  {
175  result[collision_object.id] = collision_object.pose;
176  }
177  }
178  return result;
179  }
180 
181  std::map<std::string, moveit_msgs::CollisionObject> getObjects(const std::vector<std::string>& object_ids)
182  {
183  moveit_msgs::GetPlanningScene::Request request;
184  moveit_msgs::GetPlanningScene::Response response;
185  std::map<std::string, moveit_msgs::CollisionObject> result;
186  request.components.components = request.components.WORLD_OBJECT_GEOMETRY;
187 
188  if (!getPlanningSceneServiceCall(request, response))
189  {
190  ROS_WARN_NAMED(LOGNAME, "Could not call planning scene service to get object geometries");
191  return result;
192  }
193 
194  for (const moveit_msgs::CollisionObject& collision_object : response.scene.world.collision_objects)
195  {
196  if (object_ids.empty() || std::find(object_ids.begin(), object_ids.end(), collision_object.id) != object_ids.end())
197  {
198  result[collision_object.id] = collision_object;
199  }
200  }
201  return result;
202  }
203 
204  std::map<std::string, moveit_msgs::AttachedCollisionObject>
205  getAttachedObjects(const std::vector<std::string>& object_ids)
206  {
207  moveit_msgs::GetPlanningScene::Request request;
208  moveit_msgs::GetPlanningScene::Response response;
209  std::map<std::string, moveit_msgs::AttachedCollisionObject> result;
210  request.components.components = request.components.ROBOT_STATE_ATTACHED_OBJECTS;
211 
212  if (!getPlanningSceneServiceCall(request, response))
213  {
214  ROS_WARN_NAMED(LOGNAME, "Could not call planning scene service to get attached object geometries");
215  return result;
216  }
217 
218  for (const moveit_msgs::AttachedCollisionObject& attached_collision_object :
219  response.scene.robot_state.attached_collision_objects)
220  {
221  if (object_ids.empty() ||
222  std::find(object_ids.begin(), object_ids.end(), attached_collision_object.object.id) != object_ids.end())
223  {
224  result[attached_collision_object.object.id] = attached_collision_object;
225  }
226  }
227  return result;
228  }
229 
230  moveit_msgs::PlanningScene getPlanningSceneMsg(uint32_t components)
231  {
232  moveit_msgs::GetPlanningScene::Request request;
233  moveit_msgs::GetPlanningScene::Response response;
234  request.components.components = components;
235 
236  if (!getPlanningSceneServiceCall(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 
251  {
252  ROS_WARN_NAMED(LOGNAME, "Failed to call ApplyPlanningScene service");
253  return false;
254  }
255  return response.success;
256  }
257 
258  void addCollisionObjects(const std::vector<moveit_msgs::CollisionObject>& collision_objects,
259  const std::vector<moveit_msgs::ObjectColor>& object_colors) const
260  {
261  moveit_msgs::PlanningScene planning_scene;
262  planning_scene.world.collision_objects = collision_objects;
263  planning_scene.object_colors = object_colors;
264 
265  for (size_t i = 0; i < planning_scene.object_colors.size(); ++i)
266  {
267  if (planning_scene.object_colors[i].id.empty() && i < collision_objects.size())
268  planning_scene.object_colors[i].id = collision_objects[i].id;
269  else
270  break;
271  }
272 
273  planning_scene.is_diff = true;
275  }
276 
277  void removeCollisionObjects(const std::vector<std::string>& object_ids) const
278  {
279  moveit_msgs::PlanningScene planning_scene;
280  moveit_msgs::CollisionObject object;
281  for (const std::string& object_id : object_ids)
282  {
283  object.id = object_id;
284  object.operation = object.REMOVE;
285  planning_scene.world.collision_objects.push_back(object);
286  }
287  planning_scene.is_diff = true;
289  }
290 
291  bool clear()
292  {
293  moveit_msgs::PlanningScene clear_scene;
294  clear_scene.is_diff = true;
295  clear_scene.robot_state.is_diff = true;
296  clear_scene.robot_state.attached_collision_objects.resize(1);
297  clear_scene.robot_state.attached_collision_objects[0].object.operation = moveit_msgs::CollisionObject::REMOVE;
298  clear_scene.world.collision_objects.resize(1);
299  clear_scene.world.collision_objects[0].operation = moveit_msgs::CollisionObject::REMOVE;
300 
301  return applyPlanningScene(clear_scene);
302  }
303 
304 private:
306  {
307  ros::Duration time_before_warning(5.0);
308  srv.waitForExistence(time_before_warning);
309  if (!srv.exists())
310  {
311  ROS_WARN_STREAM_NAMED(LOGNAME, "service '" << srv.getService() << "' not advertised yet. Continue waiting...");
312  srv.waitForExistence();
313  }
314  }
315 
317  {
319  {
321  }
322 
323  planning_scene_service_ = node_handle_.serviceClient<moveit_msgs::GetPlanningScene>(
325 
326  if (wait_)
327  {
329  }
330  else
331  {
333  {
334  throw std::runtime_error("ROS service not available");
335  }
336  }
337  }
338 
340  {
342  {
344  }
345 
346  apply_planning_scene_service_ = node_handle_.serviceClient<moveit_msgs::ApplyPlanningScene>(
348 
349  if (wait_)
350  {
352  }
353  else
354  {
356  {
357  throw std::runtime_error("ROS service not available");
358  }
359  }
360  }
361 
362  bool getPlanningSceneServiceCall(const moveit_msgs::GetPlanningScene::Request& request,
363  moveit_msgs::GetPlanningScene::Response& response)
364  {
367 
368  return planning_scene_service_.call(request, response);
369  }
370 
371  bool applyPlanningSceneServiceCall(const moveit_msgs::ApplyPlanningScene::Request& request,
372  moveit_msgs::ApplyPlanningScene::Response& response)
373  {
376 
378  }
379 
380  bool wait_;
382 
387  moveit::core::RobotModelConstPtr robot_model_;
388 };
389 
390 PlanningSceneInterface::PlanningSceneInterface(const std::string& ns, bool wait, bool persistent_connections)
391 {
392  impl_ = new PlanningSceneInterfaceImpl(ns, wait, persistent_connections);
393 }
394 
396 {
397  delete impl_;
398 }
399 
400 std::vector<std::string> PlanningSceneInterface::getKnownObjectNames(bool with_type)
401 {
402  return impl_->getKnownObjectNames(with_type);
403 }
404 
405 std::vector<std::string> PlanningSceneInterface::getKnownObjectNamesInROI(double minx, double miny, double minz,
406  double maxx, double maxy, double maxz,
407  bool with_type,
408  std::vector<std::string>& types)
409 {
410  return impl_->getKnownObjectNamesInROI(minx, miny, minz, maxx, maxy, maxz, with_type, types);
411 }
412 
413 std::map<std::string, geometry_msgs::Pose>
414 PlanningSceneInterface::getObjectPoses(const std::vector<std::string>& object_ids)
415 {
416  return impl_->getObjectPoses(object_ids);
417 }
418 
419 std::map<std::string, moveit_msgs::CollisionObject>
420 PlanningSceneInterface::getObjects(const std::vector<std::string>& object_ids)
421 {
422  return impl_->getObjects(object_ids);
423 }
424 
425 std::map<std::string, moveit_msgs::AttachedCollisionObject>
426 PlanningSceneInterface::getAttachedObjects(const std::vector<std::string>& object_ids)
427 {
428  return impl_->getAttachedObjects(object_ids);
429 }
430 
431 bool PlanningSceneInterface::applyCollisionObject(const moveit_msgs::CollisionObject& collision_object)
432 {
433  moveit_msgs::PlanningScene ps;
434  ps.robot_state.is_diff = true;
435  ps.is_diff = true;
436  ps.world.collision_objects.reserve(1);
437  ps.world.collision_objects.push_back(collision_object);
438  return applyPlanningScene(ps);
439 }
440 
441 bool PlanningSceneInterface::applyCollisionObject(const moveit_msgs::CollisionObject& collision_object,
442  const std_msgs::ColorRGBA& object_color)
443 {
444  moveit_msgs::PlanningScene ps;
445  ps.robot_state.is_diff = true;
446  ps.is_diff = true;
447  ps.world.collision_objects.reserve(1);
448  ps.world.collision_objects.push_back(collision_object);
449  moveit_msgs::ObjectColor oc;
450  oc.id = collision_object.id;
451  oc.color = object_color;
452  ps.object_colors.push_back(oc);
453  return applyPlanningScene(ps);
454 }
455 
456 bool PlanningSceneInterface::applyCollisionObjects(const std::vector<moveit_msgs::CollisionObject>& collision_objects,
457  const std::vector<moveit_msgs::ObjectColor>& object_colors)
458 {
459  moveit_msgs::PlanningScene ps;
460  ps.robot_state.is_diff = true;
461  ps.is_diff = true;
462  ps.world.collision_objects = collision_objects;
463  ps.object_colors = object_colors;
464 
465  for (size_t i = 0; i < ps.object_colors.size(); ++i)
466  {
467  if (ps.object_colors[i].id.empty() && i < collision_objects.size())
468  ps.object_colors[i].id = collision_objects[i].id;
469  else
470  break;
471  }
472 
473  return applyPlanningScene(ps);
474 }
475 
476 bool PlanningSceneInterface::applyAttachedCollisionObject(const moveit_msgs::AttachedCollisionObject& collision_object)
477 {
478  moveit_msgs::PlanningScene ps;
479  ps.robot_state.is_diff = true;
480  ps.is_diff = true;
481  ps.robot_state.attached_collision_objects.reserve(1);
482  ps.robot_state.attached_collision_objects.push_back(collision_object);
483  return applyPlanningScene(ps);
484 }
485 
487  const std::vector<moveit_msgs::AttachedCollisionObject>& collision_objects)
488 {
489  moveit_msgs::PlanningScene ps;
490  ps.robot_state.is_diff = true;
491  ps.is_diff = true;
492  ps.robot_state.attached_collision_objects = collision_objects;
493  return applyPlanningScene(ps);
494 }
495 
496 moveit_msgs::PlanningScene PlanningSceneInterface::getPlanningSceneMsg(uint32_t components)
497 {
498  return impl_->getPlanningSceneMsg(components);
499 }
500 
501 bool PlanningSceneInterface::applyPlanningScene(const moveit_msgs::PlanningScene& ps)
502 {
503  return impl_->applyPlanningScene(ps);
504 }
505 
506 void PlanningSceneInterface::addCollisionObjects(const std::vector<moveit_msgs::CollisionObject>& collision_objects,
507  const std::vector<moveit_msgs::ObjectColor>& object_colors) const
508 {
509  impl_->addCollisionObjects(collision_objects, object_colors);
510 }
511 
512 void PlanningSceneInterface::removeCollisionObjects(const std::vector<std::string>& object_ids) const
513 {
514  impl_->removeCollisionObjects(object_ids);
515 }
516 
518 {
519  return impl_->clear();
520 }
521 
522 } // namespace planning_interface
523 } // namespace moveit
response
const std::string response
move_group::GET_PLANNING_SCENE_SERVICE_NAME
static const std::string GET_PLANNING_SCENE_SERVICE_NAME
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::connectGetPlanningSceneService
void connectGetPlanningSceneService()
Definition: planning_scene_interface/src/planning_scene_interface.cpp:380
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:540
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: planning_scene_interface/src/planning_scene_interface.cpp:451
ros::ServiceClient::exists
bool exists()
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::clear
bool clear()
Definition: planning_scene_interface/src/planning_scene_interface.cpp:355
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:581
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::persistent_connections_
bool persistent_connections_
Definition: planning_scene_interface/src/planning_scene_interface.cpp:445
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:158
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:550
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::PlanningSceneInterfaceImpl
PlanningSceneInterfaceImpl(const std::string &ns="", bool wait=true, bool persistent_connections=false)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:118
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::planning_scene_service_
ros::ServiceClient planning_scene_service_
Definition: planning_scene_interface/src/planning_scene_interface.cpp:448
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:464
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::waitForService
void waitForService(ros::ServiceClient &srv)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:369
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:322
wait
void wait(int seconds)
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::connectApplyPlanningSceneService
void connectApplyPlanningSceneService()
Definition: planning_scene_interface/src/planning_scene_interface.cpp:403
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:565
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:341
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:478
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getPlanningSceneServiceCall
bool getPlanningSceneServiceCall(const moveit_msgs::GetPlanningScene::Request &request, moveit_msgs::GetPlanningScene::Response &response)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:426
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:222
moveit::planning_interface::PlanningSceneInterface::impl_
PlanningSceneInterfaceImpl * impl_
Definition: planning_scene_interface.h:222
moveit::planning_interface::PlanningSceneInterface::~PlanningSceneInterface
~PlanningSceneInterface()
Definition: planning_scene_interface/src/planning_scene_interface.cpp:459
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:576
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getPlanningSceneMsg
moveit_msgs::PlanningScene getPlanningSceneMsg(uint32_t components)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:294
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:450
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:447
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::applyPlanningSceneServiceCall
bool applyPlanningSceneServiceCall(const moveit_msgs::ApplyPlanningScene::Request &request, moveit_msgs::ApplyPlanningScene::Response &response)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:435
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:484
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:520
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::wait_
bool wait_
Definition: planning_scene_interface/src/planning_scene_interface.cpp:444
planning_interface
ros::ServiceClient::isValid
bool isValid() const
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
ros::service::waitForService
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
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:449
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:245
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterfaceImpl::getKnownObjectNames
std::vector< std::string > getKnownObjectNames(bool with_type)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:135
moveit::planning_interface::PlanningSceneInterface::PlanningSceneInterface
PlanningSceneInterface(const std::string &ns="", bool wait=true, bool persistent_connections=false)
Definition: planning_scene_interface/src/planning_scene_interface.cpp:454
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:490
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:495
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:269
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:570
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:469
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:560


planning_interface
Author(s): Ioan Sucan
autogenerated on Sat May 3 2025 02:27:23