moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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>
45
46namespace moveit
47{
48namespace planning_interface
49{
50
52{
53public:
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 || primitive_pose.position.y < miny ||
140 primitive_pose.position.y > maxy || primitive_pose.position.z < minz || primitive_pose.position.z > maxz)
141 {
142 good = false;
143 break;
144 }
145 }
146 if (good)
147 {
148 result.push_back(collision_object.id);
149 if (with_type)
150 types.push_back(collision_object.type.key);
151 }
152 }
153 return result;
154 }
155
156 std::map<std::string, geometry_msgs::msg::Pose> getObjectPoses(const std::vector<std::string>& object_ids)
157 {
158 auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
159 moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
160 std::map<std::string, geometry_msgs::msg::Pose> result;
161 request->components.components = request->components.WORLD_OBJECT_GEOMETRY;
162
163 auto res = planning_scene_service_->async_send_request(request);
164 if (rclcpp::spin_until_future_complete(node_, res) == rclcpp::FutureReturnCode::SUCCESS)
165 {
166 response = res.get();
167 for (const moveit_msgs::msg::CollisionObject& collision_object : response->scene.world.collision_objects)
168 {
169 if (std::find(object_ids.begin(), object_ids.end(), collision_object.id) != object_ids.end())
170 {
171 result[collision_object.id] = collision_object.pose;
172 }
173 }
174 }
175 return result;
176 }
177
178 std::map<std::string, moveit_msgs::msg::CollisionObject> getObjects(const std::vector<std::string>& object_ids)
179 {
180 auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
181 moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
182 std::map<std::string, moveit_msgs::msg::CollisionObject> result;
183 request->components.components = request->components.WORLD_OBJECT_GEOMETRY;
184
185 auto res = planning_scene_service_->async_send_request(request);
186 if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
187 {
188 RCLCPP_WARN(node_->get_logger(), "Could not call planning scene service to get object geometries");
189 return result;
190 }
191 response = res.get();
192
193 for (const moveit_msgs::msg::CollisionObject& collision_object : response->scene.world.collision_objects)
194 {
195 if (object_ids.empty() || std::find(object_ids.begin(), object_ids.end(), collision_object.id) != object_ids.end())
196 {
197 result[collision_object.id] = collision_object;
198 }
199 }
200 return result;
201 }
202
203 std::map<std::string, moveit_msgs::msg::AttachedCollisionObject>
204 getAttachedObjects(const std::vector<std::string>& object_ids)
205 {
206 auto request = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
207 moveit_msgs::srv::GetPlanningScene::Response::SharedPtr response;
208 std::map<std::string, moveit_msgs::msg::AttachedCollisionObject> result;
209 request->components.components = request->components.ROBOT_STATE_ATTACHED_OBJECTS;
210
211 auto res = planning_scene_service_->async_send_request(request);
212 if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
213 {
214 RCLCPP_WARN(node_->get_logger(), "Could not call planning scene service to get attached object geometries");
215 return result;
216 }
217 response = res.get();
218
219 for (const moveit_msgs::msg::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 bool applyPlanningScene(const moveit_msgs::msg::PlanningScene& planning_scene)
232 {
233 auto request = std::make_shared<moveit_msgs::srv::ApplyPlanningScene::Request>();
234 moveit_msgs::srv::ApplyPlanningScene::Response::SharedPtr response;
235 request->scene = planning_scene;
236
237 auto res = apply_planning_scene_service_->async_send_request(request);
238 if (rclcpp::spin_until_future_complete(node_, res) != rclcpp::FutureReturnCode::SUCCESS)
239 {
240 RCLCPP_WARN(node_->get_logger(), "Failed to call ApplyPlanningScene service");
241 }
242 response = res.get();
243 return response->success;
244 }
245
246 void addCollisionObjects(const std::vector<moveit_msgs::msg::CollisionObject>& collision_objects,
247 const std::vector<moveit_msgs::msg::ObjectColor>& object_colors) const
248 {
249 moveit_msgs::msg::PlanningScene planning_scene;
250 planning_scene.world.collision_objects = collision_objects;
251 planning_scene.object_colors = object_colors;
252
253 for (size_t i = 0; i < planning_scene.object_colors.size(); ++i)
254 {
255 if (planning_scene.object_colors[i].id.empty() && i < collision_objects.size())
256 {
257 planning_scene.object_colors[i].id = collision_objects[i].id;
258 }
259 else
260 {
261 break;
262 }
263 }
264
265 planning_scene.is_diff = true;
266 planning_scene_diff_publisher_->publish(planning_scene);
267 }
268
269 void removeCollisionObjects(const std::vector<std::string>& object_ids) const
270 {
271 moveit_msgs::msg::PlanningScene planning_scene;
272 moveit_msgs::msg::CollisionObject object;
273 for (const std::string& object_id : object_ids)
274 {
275 object.id = object_id;
276 object.operation = object.REMOVE;
277 planning_scene.world.collision_objects.push_back(object);
278 }
279 planning_scene.is_diff = true;
280 planning_scene_diff_publisher_->publish(planning_scene);
281 }
282
283private:
284 void waitForService(const std::shared_ptr<rclcpp::ClientBase>& srv)
285 {
286 // rclcpp::Duration time_before_warning(5.0);
287 // srv.waitForExistence(time_before_warning);
288 std::chrono::duration<double> d(5.0);
289 srv->wait_for_service(std::chrono::duration_cast<std::chrono::nanoseconds>(d));
290 if (!srv->service_is_ready())
291 {
292 RCLCPP_WARN_STREAM(node_->get_logger(),
293 "service '" << srv->get_service_name() << "' not advertised yet. Continue waiting...");
294 srv->wait_for_service();
295 }
296 }
297
298 rclcpp::Node::SharedPtr node_;
299 rclcpp::Client<moveit_msgs::srv::GetPlanningScene>::SharedPtr planning_scene_service_;
300 rclcpp::Client<moveit_msgs::srv::ApplyPlanningScene>::SharedPtr apply_planning_scene_service_;
301 rclcpp::Publisher<moveit_msgs::msg::PlanningScene>::SharedPtr planning_scene_diff_publisher_;
302 moveit::core::RobotModelConstPtr robot_model_;
303};
304
305PlanningSceneInterface::PlanningSceneInterface(const std::string& ns, bool wait)
306{
307 impl_ = new PlanningSceneInterfaceImpl(ns, wait);
308}
309
314
315std::vector<std::string> PlanningSceneInterface::getKnownObjectNames(bool with_type)
316{
317 return impl_->getKnownObjectNames(with_type);
318}
319
320std::vector<std::string> PlanningSceneInterface::getKnownObjectNamesInROI(double minx, double miny, double minz,
321 double maxx, double maxy, double maxz,
322 bool with_type,
323 std::vector<std::string>& types)
324{
325 return impl_->getKnownObjectNamesInROI(minx, miny, minz, maxx, maxy, maxz, with_type, types);
326}
327
328std::map<std::string, geometry_msgs::msg::Pose>
329PlanningSceneInterface::getObjectPoses(const std::vector<std::string>& object_ids)
330{
331 return impl_->getObjectPoses(object_ids);
332}
333
334std::map<std::string, moveit_msgs::msg::CollisionObject>
335PlanningSceneInterface::getObjects(const std::vector<std::string>& object_ids)
336{
337 return impl_->getObjects(object_ids);
338}
339
340std::map<std::string, moveit_msgs::msg::AttachedCollisionObject>
341PlanningSceneInterface::getAttachedObjects(const std::vector<std::string>& object_ids)
342{
343 return impl_->getAttachedObjects(object_ids);
344}
345
346bool PlanningSceneInterface::applyCollisionObject(const moveit_msgs::msg::CollisionObject& collision_object)
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 return applyPlanningScene(ps);
354}
355
356bool PlanningSceneInterface::applyCollisionObject(const moveit_msgs::msg::CollisionObject& collision_object,
357 const std_msgs::msg::ColorRGBA& object_color)
358{
359 moveit_msgs::msg::PlanningScene ps;
360 ps.robot_state.is_diff = true;
361 ps.is_diff = true;
362 ps.world.collision_objects.reserve(1);
363 ps.world.collision_objects.push_back(collision_object);
364 moveit_msgs::msg::ObjectColor oc;
365 oc.id = collision_object.id;
366 oc.color = object_color;
367 ps.object_colors.push_back(oc);
368 return applyPlanningScene(ps);
369}
370
372 const std::vector<moveit_msgs::msg::CollisionObject>& collision_objects,
373 const std::vector<moveit_msgs::msg::ObjectColor>& object_colors)
374{
375 moveit_msgs::msg::PlanningScene ps;
376 ps.robot_state.is_diff = true;
377 ps.is_diff = true;
378 ps.world.collision_objects = collision_objects;
379 ps.object_colors = object_colors;
380
381 for (size_t i = 0; i < ps.object_colors.size(); ++i)
382 {
383 if (ps.object_colors[i].id.empty() && i < collision_objects.size())
384 {
385 ps.object_colors[i].id = collision_objects[i].id;
386 }
387 else
388 {
389 break;
390 }
391 }
392
393 return applyPlanningScene(ps);
394}
395
397 const moveit_msgs::msg::AttachedCollisionObject& collision_object)
398{
399 moveit_msgs::msg::PlanningScene ps;
400 ps.robot_state.is_diff = true;
401 ps.is_diff = true;
402 ps.robot_state.attached_collision_objects.reserve(1);
403 ps.robot_state.attached_collision_objects.push_back(collision_object);
404 return applyPlanningScene(ps);
405}
406
408 const std::vector<moveit_msgs::msg::AttachedCollisionObject>& collision_objects)
409{
410 moveit_msgs::msg::PlanningScene ps;
411 ps.robot_state.is_diff = true;
412 ps.is_diff = true;
413 ps.robot_state.attached_collision_objects = collision_objects;
414 return applyPlanningScene(ps);
415}
416
417bool PlanningSceneInterface::applyPlanningScene(const moveit_msgs::msg::PlanningScene& ps)
418{
419 return impl_->applyPlanningScene(ps);
420}
421
422void PlanningSceneInterface::addCollisionObjects(const std::vector<moveit_msgs::msg::CollisionObject>& collision_objects,
423 const std::vector<moveit_msgs::msg::ObjectColor>& object_colors) const
424{
425 impl_->addCollisionObjects(collision_objects, object_colors);
426}
427
428void PlanningSceneInterface::removeCollisionObjects(const std::vector<std::string>& object_ids) const
429{
430 impl_->removeCollisionObjects(object_ids);
431}
432} // namespace planning_interface
433} // namespace moveit
std::map< std::string, geometry_msgs::msg::Pose > getObjectPoses(const std::vector< std::string > &object_ids)
std::map< std::string, moveit_msgs::msg::AttachedCollisionObject > getAttachedObjects(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
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)
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.