moveit2
The MoveIt Motion Planning Framework for ROS 2.
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/srv/get_planning_scene.hpp>
40 #include <moveit_msgs/srv/apply_planning_scene.hpp>
41 #include <algorithm>
42 #include <rclcpp/executors.hpp>
43 #include <rclcpp/future_return_code.hpp>
44 #include <moveit/utils/logger.hpp>
45 
46 namespace moveit
47 {
48 namespace planning_interface
49 {
50 
52 {
53 public:
54  explicit PlanningSceneInterfaceImpl(const std::string& ns = "", bool wait = true)
55  {
56  rclcpp::NodeOptions options;
57  options.arguments({ "--ros-args", "-r",
58  "__node:=" + std::string("planning_scene_interface_") +
59  std::to_string(reinterpret_cast<std::size_t>(this)) });
60  node_ = rclcpp::Node::make_shared("_", ns, options);
61  moveit::setNodeLoggerName(node_->get_name());
62  planning_scene_diff_publisher_ = node_->create_publisher<moveit_msgs::msg::PlanningScene>("planning_scene", 1);
63  planning_scene_service_ =
64  node_->create_client<moveit_msgs::srv::GetPlanningScene>(move_group::GET_PLANNING_SCENE_SERVICE_NAME);
65  apply_planning_scene_service_ =
66  node_->create_client<moveit_msgs::srv::ApplyPlanningScene>(move_group::APPLY_PLANNING_SCENE_SERVICE_NAME);
67 
68  if (wait)
69  {
70  waitForService(std::static_pointer_cast<rclcpp::ClientBase>(planning_scene_service_));
71  waitForService(std::static_pointer_cast<rclcpp::ClientBase>(apply_planning_scene_service_));
72  }
73  }
74 
75  std::vector<std::string> getKnownObjectNames(bool with_type)
76  {
77  auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
78  moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
79  std::vector<std::string> result;
80  request->components.components = request->components.WORLD_OBJECT_NAMES;
81 
82  auto res = planning_scene_service_->async_send_request(request);
83  if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
84  {
85  return result;
86  }
87  response = res.get();
88 
89  if (with_type)
90  {
91  for (const moveit_msgs::msg::CollisionObject& collision_object : response->scene.world.collision_objects)
92  {
93  if (!collision_object.type.key.empty())
94  result.push_back(collision_object.id);
95  }
96  }
97  else
98  {
99  for (const moveit_msgs::msg::CollisionObject& collision_object : response->scene.world.collision_objects)
100  result.push_back(collision_object.id);
101  }
102  return result;
103  }
104 
105  std::vector<std::string> getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy,
106  double maxz, bool with_type, std::vector<std::string>& types)
107  {
108  auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
109  moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
110  std::vector<std::string> result;
111  request->components.components = request->components.WORLD_OBJECT_GEOMETRY;
112 
113  auto res = planning_scene_service_->async_send_request(request);
114  if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
115  {
116  RCLCPP_WARN(node_->get_logger(), "Could not call planning scene service to get object names");
117  return result;
118  }
119  response = res.get();
120 
121  for (const moveit_msgs::msg::CollisionObject& collision_object : response->scene.world.collision_objects)
122  {
123  if (with_type && collision_object.type.key.empty())
124  continue;
125  if (collision_object.mesh_poses.empty() && collision_object.primitive_poses.empty())
126  continue;
127  bool good = true;
128  for (const geometry_msgs::msg::Pose& mesh_pose : collision_object.mesh_poses)
129  {
130  if (!(mesh_pose.position.x >= minx && mesh_pose.position.x <= maxx && mesh_pose.position.y >= miny &&
131  mesh_pose.position.y <= maxy && mesh_pose.position.z >= minz && mesh_pose.position.z <= maxz))
132  {
133  good = false;
134  break;
135  }
136  }
137  for (const geometry_msgs::msg::Pose& primitive_pose : collision_object.primitive_poses)
138  {
139  if (!(primitive_pose.position.x >= minx && primitive_pose.position.x <= maxx &&
140  primitive_pose.position.y >= miny && primitive_pose.position.y <= maxy &&
141  primitive_pose.position.z >= minz && primitive_pose.position.z <= maxz))
142  {
143  good = false;
144  break;
145  }
146  }
147  if (good)
148  {
149  result.push_back(collision_object.id);
150  if (with_type)
151  types.push_back(collision_object.type.key);
152  }
153  }
154  return result;
155  }
156 
157  std::map<std::string, geometry_msgs::msg::Pose> getObjectPoses(const std::vector<std::string>& object_ids)
158  {
159  auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
160  moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
161  std::map<std::string, geometry_msgs::msg::Pose> result;
162  request->components.components = request->components.WORLD_OBJECT_GEOMETRY;
163 
164  auto res = planning_scene_service_->async_send_request(request);
165  if (rclcpp::spin_until_future_complete(node_, res) == rclcpp::FutureReturnCode::SUCCESS)
166  {
167  response = res.get();
168  for (const moveit_msgs::msg::CollisionObject& collision_object : response->scene.world.collision_objects)
169  {
170  if (std::find(object_ids.begin(), object_ids.end(), collision_object.id) != object_ids.end())
171  {
172  result[collision_object.id] = collision_object.pose;
173  }
174  }
175  }
176  return result;
177  }
178 
179  std::map<std::string, moveit_msgs::msg::CollisionObject> getObjects(const std::vector<std::string>& object_ids)
180  {
181  auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
182  moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
183  std::map<std::string, moveit_msgs::msg::CollisionObject> result;
184  request->components.components = request->components.WORLD_OBJECT_GEOMETRY;
185 
186  auto res = planning_scene_service_->async_send_request(request);
187  if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
188  {
189  RCLCPP_WARN(node_->get_logger(), "Could not call planning scene service to get object geometries");
190  return result;
191  }
192  response = res.get();
193 
194  for (const moveit_msgs::msg::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::msg::AttachedCollisionObject>
205  getAttachedObjects(const std::vector<std::string>& object_ids)
206  {
207  auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
208  moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
209  std::map<std::string, moveit_msgs::msg::AttachedCollisionObject> result;
210  request->components.components = request->components.ROBOT_STATE_ATTACHED_OBJECTS;
211 
212  auto res = planning_scene_service_->async_send_request(request);
213  if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
214  {
215  RCLCPP_WARN(node_->get_logger(), "Could not call planning scene service to get attached object geometries");
216  return result;
217  }
218  response = res.get();
219 
220  for (const moveit_msgs::msg::AttachedCollisionObject& attached_collision_object :
221  response->scene.robot_state.attached_collision_objects)
222  {
223  if (object_ids.empty() ||
224  std::find(object_ids.begin(), object_ids.end(), attached_collision_object.object.id) != object_ids.end())
225  {
226  result[attached_collision_object.object.id] = attached_collision_object;
227  }
228  }
229  return result;
230  }
231 
232  bool applyPlanningScene(const moveit_msgs::msg::PlanningScene& planning_scene)
233  {
234  auto request = std::make_shared<moveit_msgs::srv::ApplyPlanningScene::Request>();
235  moveit_msgs::srv::ApplyPlanningScene::Response::SharedPtr response;
236  request->scene = planning_scene;
237 
238  auto res = apply_planning_scene_service_->async_send_request(request);
239  if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
240  {
241  RCLCPP_WARN(node_->get_logger(), "Failed to call ApplyPlanningScene service");
242  }
243  response = res.get();
244  return response->success;
245  }
246 
247  void addCollisionObjects(const std::vector<moveit_msgs::msg::CollisionObject>& collision_objects,
248  const std::vector<moveit_msgs::msg::ObjectColor>& object_colors) const
249  {
250  moveit_msgs::msg::PlanningScene planning_scene;
251  planning_scene.world.collision_objects = collision_objects;
252  planning_scene.object_colors = object_colors;
253 
254  for (size_t i = 0; i < planning_scene.object_colors.size(); ++i)
255  {
256  if (planning_scene.object_colors[i].id.empty() && i < collision_objects.size())
257  {
258  planning_scene.object_colors[i].id = collision_objects[i].id;
259  }
260  else
261  {
262  break;
263  }
264  }
265 
266  planning_scene.is_diff = true;
267  planning_scene_diff_publisher_->publish(planning_scene);
268  }
269 
270  void removeCollisionObjects(const std::vector<std::string>& object_ids) const
271  {
272  moveit_msgs::msg::PlanningScene planning_scene;
273  moveit_msgs::msg::CollisionObject object;
274  for (const std::string& object_id : object_ids)
275  {
276  object.id = object_id;
277  object.operation = object.REMOVE;
278  planning_scene.world.collision_objects.push_back(object);
279  }
280  planning_scene.is_diff = true;
281  planning_scene_diff_publisher_->publish(planning_scene);
282  }
283 
284 private:
285  void waitForService(const std::shared_ptr<rclcpp::ClientBase>& srv)
286  {
287  // rclcpp::Duration time_before_warning(5.0);
288  // srv.waitForExistence(time_before_warning);
289  std::chrono::duration<double> d(5.0);
290  srv->wait_for_service(std::chrono::duration_cast<std::chrono::nanoseconds>(d));
291  if (!srv->service_is_ready())
292  {
293  RCLCPP_WARN_STREAM(node_->get_logger(),
294  "service '" << srv->get_service_name() << "' not advertised yet. Continue waiting...");
295  srv->wait_for_service();
296  }
297  }
298 
299  rclcpp::Node::SharedPtr node_;
300  rclcpp::Client<moveit_msgs::srv::GetPlanningScene>::SharedPtr planning_scene_service_;
301  rclcpp::Client<moveit_msgs::srv::ApplyPlanningScene>::SharedPtr apply_planning_scene_service_;
302  rclcpp::Publisher<moveit_msgs::msg::PlanningScene>::SharedPtr planning_scene_diff_publisher_;
303  moveit::core::RobotModelConstPtr robot_model_;
304 };
305 
306 PlanningSceneInterface::PlanningSceneInterface(const std::string& ns, bool wait)
307 {
308  impl_ = new PlanningSceneInterfaceImpl(ns, wait);
309 }
310 
312 {
313  delete impl_;
314 }
315 
316 std::vector<std::string> PlanningSceneInterface::getKnownObjectNames(bool with_type)
317 {
318  return impl_->getKnownObjectNames(with_type);
319 }
320 
321 std::vector<std::string> PlanningSceneInterface::getKnownObjectNamesInROI(double minx, double miny, double minz,
322  double maxx, double maxy, double maxz,
323  bool with_type,
324  std::vector<std::string>& types)
325 {
326  return impl_->getKnownObjectNamesInROI(minx, miny, minz, maxx, maxy, maxz, with_type, types);
327 }
328 
329 std::map<std::string, geometry_msgs::msg::Pose>
330 PlanningSceneInterface::getObjectPoses(const std::vector<std::string>& object_ids)
331 {
332  return impl_->getObjectPoses(object_ids);
333 }
334 
335 std::map<std::string, moveit_msgs::msg::CollisionObject>
336 PlanningSceneInterface::getObjects(const std::vector<std::string>& object_ids)
337 {
338  return impl_->getObjects(object_ids);
339 }
340 
341 std::map<std::string, moveit_msgs::msg::AttachedCollisionObject>
342 PlanningSceneInterface::getAttachedObjects(const std::vector<std::string>& object_ids)
343 {
344  return impl_->getAttachedObjects(object_ids);
345 }
346 
347 bool PlanningSceneInterface::applyCollisionObject(const moveit_msgs::msg::CollisionObject& collision_object)
348 {
349  moveit_msgs::msg::PlanningScene ps;
350  ps.robot_state.is_diff = true;
351  ps.is_diff = true;
352  ps.world.collision_objects.reserve(1);
353  ps.world.collision_objects.push_back(collision_object);
354  return applyPlanningScene(ps);
355 }
356 
357 bool PlanningSceneInterface::applyCollisionObject(const moveit_msgs::msg::CollisionObject& collision_object,
358  const std_msgs::msg::ColorRGBA& object_color)
359 {
360  moveit_msgs::msg::PlanningScene ps;
361  ps.robot_state.is_diff = true;
362  ps.is_diff = true;
363  ps.world.collision_objects.reserve(1);
364  ps.world.collision_objects.push_back(collision_object);
365  moveit_msgs::msg::ObjectColor oc;
366  oc.id = collision_object.id;
367  oc.color = object_color;
368  ps.object_colors.push_back(oc);
369  return applyPlanningScene(ps);
370 }
371 
373  const std::vector<moveit_msgs::msg::CollisionObject>& collision_objects,
374  const std::vector<moveit_msgs::msg::ObjectColor>& object_colors)
375 {
376  moveit_msgs::msg::PlanningScene ps;
377  ps.robot_state.is_diff = true;
378  ps.is_diff = true;
379  ps.world.collision_objects = collision_objects;
380  ps.object_colors = object_colors;
381 
382  for (size_t i = 0; i < ps.object_colors.size(); ++i)
383  {
384  if (ps.object_colors[i].id.empty() && i < collision_objects.size())
385  {
386  ps.object_colors[i].id = collision_objects[i].id;
387  }
388  else
389  {
390  break;
391  }
392  }
393 
394  return applyPlanningScene(ps);
395 }
396 
398  const moveit_msgs::msg::AttachedCollisionObject& collision_object)
399 {
400  moveit_msgs::msg::PlanningScene ps;
401  ps.robot_state.is_diff = true;
402  ps.is_diff = true;
403  ps.robot_state.attached_collision_objects.reserve(1);
404  ps.robot_state.attached_collision_objects.push_back(collision_object);
405  return applyPlanningScene(ps);
406 }
407 
409  const std::vector<moveit_msgs::msg::AttachedCollisionObject>& collision_objects)
410 {
411  moveit_msgs::msg::PlanningScene ps;
412  ps.robot_state.is_diff = true;
413  ps.is_diff = true;
414  ps.robot_state.attached_collision_objects = collision_objects;
415  return applyPlanningScene(ps);
416 }
417 
418 bool PlanningSceneInterface::applyPlanningScene(const moveit_msgs::msg::PlanningScene& ps)
419 {
420  return impl_->applyPlanningScene(ps);
421 }
422 
423 void PlanningSceneInterface::addCollisionObjects(const std::vector<moveit_msgs::msg::CollisionObject>& collision_objects,
424  const std::vector<moveit_msgs::msg::ObjectColor>& object_colors) const
425 {
426  impl_->addCollisionObjects(collision_objects, object_colors);
427 }
428 
429 void PlanningSceneInterface::removeCollisionObjects(const std::vector<std::string>& object_ids) const
430 {
431  impl_->removeCollisionObjects(object_ids);
432 }
433 } // namespace planning_interface
434 } // namespace moveit
std::map< std::string, moveit_msgs::msg::AttachedCollisionObject > getAttachedObjects(const std::vector< std::string > &object_ids)
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)
std::map< std::string, geometry_msgs::msg::Pose > getObjectPoses(const std::vector< std::string > &object_ids)
std::map< std::string, moveit_msgs::msg::CollisionObject > getObjects(const std::vector< std::string > &object_ids)
bool applyPlanningScene(const moveit_msgs::msg::PlanningScene &planning_scene)
void removeCollisionObjects(const std::vector< std::string > &object_ids) const
void addCollisionObjects(const std::vector< moveit_msgs::msg::CollisionObject > &collision_objects, const std::vector< moveit_msgs::msg::ObjectColor > &object_colors) const
bool applyAttachedCollisionObject(const moveit_msgs::msg::AttachedCollisionObject &attached_collision_object)
Apply attached collision object to the planning scene of the move_group node synchronously....
std::map< std::string, moveit_msgs::msg::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,...
bool applyPlanningScene(const moveit_msgs::msg::PlanningScene &ps)
Update the planning_scene of the move_group node with the given ps synchronously. Other PlanningScene...
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...
bool applyAttachedCollisionObjects(const std::vector< moveit_msgs::msg::AttachedCollisionObject > &attached_collision_objects)
Apply attached collision objects to the planning scene of the move_group node synchronously....
std::map< std::string, moveit_msgs::msg::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...
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...
PlanningSceneInterface(const std::string &ns="", bool wait=true)
void removeCollisionObjects(const std::vector< std::string > &object_ids) const
Remove collision objects from the world via /planning_scene.
std::map< std::string, geometry_msgs::msg::Pose > getObjectPoses(const std::vector< std::string > &object_ids)
Get the poses from the objects identified by the given object ids list.
bool applyCollisionObject(const moveit_msgs::msg::CollisionObject &collision_object)
Apply collision object to the planning scene of the move_group node synchronously....
bool applyCollisionObjects(const std::vector< moveit_msgs::msg::CollisionObject > &collision_objects, const std::vector< moveit_msgs::msg::ObjectColor > &object_colors=std::vector< moveit_msgs::msg::ObjectColor >())
Apply collision objects to the planning scene of the move_group node synchronously....
void addCollisionObjects(const std::vector< moveit_msgs::msg::CollisionObject > &collision_objects, const std::vector< moveit_msgs::msg::ObjectColor > &object_colors=std::vector< moveit_msgs::msg::ObjectColor >()) const
Add collision objects to the world via /planning_scene. Make sure object.operation is set to object....
Main namespace for MoveIt.
Definition: exceptions.h:43
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
Definition: logger.cpp:73
This namespace includes the base class for MoveIt planners.
This namespace includes the central class for representing planning contexts.