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