moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_scene.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, 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 */
36 
37 #include <boost/algorithm/string.hpp>
41 #include <geometric_shapes/shape_operations.h>
48 #include <octomap_msgs/conversions.h>
49 #include <rclcpp/logger.hpp>
50 #include <rclcpp/logging.hpp>
51 #include <tf2_eigen/tf2_eigen.hpp>
52 #include <memory>
53 #include <set>
54 
55 namespace planning_scene
56 {
57 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_planning_scene.planning_scene");
58 
59 const std::string PlanningScene::OCTOMAP_NS = "<octomap>";
60 const std::string PlanningScene::DEFAULT_SCENE_NAME = "(noname)";
61 
63 {
64 public:
65  SceneTransforms(const PlanningScene* scene) : Transforms(scene->getRobotModel()->getModelFrame()), scene_(scene)
66  {
67  }
68 
69  bool canTransform(const std::string& from_frame) const override
70  {
71  return scene_->knowsFrameTransform(from_frame);
72  }
73 
74  bool isFixedFrame(const std::string& frame) const override
75  {
76  if (frame.empty())
77  return false;
78  if (Transforms::isFixedFrame(frame))
79  return true;
80  if (frame[0] == '/')
81  return knowsObjectFrame(frame.substr(1));
82  else
83  return knowsObjectFrame(frame);
84  }
85 
86  const Eigen::Isometry3d& getTransform(const std::string& from_frame) const override
87  { // the call below also calls Transforms::getTransform() too
88  return scene_->getFrameTransform(from_frame);
89  }
90 
91 private:
92  // Returns true if frame_id is the name of an object or the name of a subframe on an object
93  bool knowsObjectFrame(const std::string& frame_id) const
94  {
95  return scene_->getWorld()->knowsTransform(frame_id);
96  }
97 
98  const PlanningScene* scene_;
99 };
100 
101 bool PlanningScene::isEmpty(const moveit_msgs::msg::PlanningScene& msg)
102 {
103  return moveit::core::isEmpty(msg);
104 }
105 
106 bool PlanningScene::isEmpty(const moveit_msgs::msg::RobotState& msg)
107 {
108  return moveit::core::isEmpty(msg);
109 }
110 
111 bool PlanningScene::isEmpty(const moveit_msgs::msg::PlanningSceneWorld& msg)
112 {
113  return moveit::core::isEmpty(msg);
114 }
115 
116 PlanningScene::PlanningScene(const moveit::core::RobotModelConstPtr& robot_model,
117  const collision_detection::WorldPtr& world)
118 
119  : robot_model_(robot_model), world_(world), world_const_(world)
120 {
121  initialize();
122 }
123 
124 PlanningScene::PlanningScene(const urdf::ModelInterfaceSharedPtr& urdf_model,
125  const srdf::ModelConstSharedPtr& srdf_model, const collision_detection::WorldPtr& world)
126  : world_(world), world_const_(world)
127 {
128  if (!urdf_model)
129  throw moveit::ConstructException("The URDF model cannot be nullptr");
130 
131  if (!srdf_model)
132  throw moveit::ConstructException("The SRDF model cannot be nullptr");
133 
134  robot_model_ = createRobotModel(urdf_model, srdf_model);
135  if (!robot_model_)
136  throw moveit::ConstructException("Could not create RobotModel");
137 
138  initialize();
139 }
140 
142 {
143  if (current_world_object_update_callback_)
144  world_->removeObserver(current_world_object_update_observer_handle_);
145 }
146 
147 void PlanningScene::initialize()
148 {
149  name_ = DEFAULT_SCENE_NAME;
150 
151  scene_transforms_ = std::make_shared<SceneTransforms>(this);
152 
153  robot_state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
154  robot_state_->setToDefaultValues();
155  robot_state_->update();
156 
157  acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(*getRobotModel()->getSRDF());
158 
160 }
161 
162 // return nullptr on failure
163 moveit::core::RobotModelPtr PlanningScene::createRobotModel(const urdf::ModelInterfaceSharedPtr& urdf_model,
164  const srdf::ModelConstSharedPtr& srdf_model)
165 {
166  auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
167  if (!robot_model || !robot_model->getRootJoint())
168  return moveit::core::RobotModelPtr();
169 
170  return robot_model;
171 }
172 
173 PlanningScene::PlanningScene(const PlanningSceneConstPtr& parent) : parent_(parent)
174 {
175  if (!parent_)
176  throw moveit::ConstructException("nullptr parent pointer for planning scene");
177 
178  if (!parent_->getName().empty())
179  name_ = parent_->getName() + "+";
180 
181  robot_model_ = parent_->robot_model_;
182 
183  // maintain a separate world. Copy on write ensures that most of the object
184  // info is shared until it is modified.
185  world_ = std::make_shared<collision_detection::World>(*parent_->world_);
186  world_const_ = world_;
187 
188  // record changes to the world
189  world_diff_ = std::make_shared<collision_detection::WorldDiff>(world_);
190 
191  allocateCollisionDetector(parent_->collision_detector_->alloc_, parent_->collision_detector_);
192  collision_detector_->copyPadding(*parent_->collision_detector_);
193 }
194 
195 PlanningScenePtr PlanningScene::clone(const PlanningSceneConstPtr& scene)
196 {
197  PlanningScenePtr result = scene->diff();
198  result->decoupleParent();
199  result->setName(scene->getName());
200  return result;
201 }
202 
203 PlanningScenePtr PlanningScene::diff() const
204 {
205  return PlanningScenePtr(new PlanningScene(shared_from_this()));
206 }
207 
208 PlanningScenePtr PlanningScene::diff(const moveit_msgs::msg::PlanningScene& msg) const
209 {
210  PlanningScenePtr result = diff();
211  result->setPlanningSceneDiffMsg(msg);
212  return result;
213 }
214 
215 void PlanningScene::CollisionDetector::copyPadding(const PlanningScene::CollisionDetector& src)
216 {
217  cenv_->setLinkPadding(src.getCollisionEnv()->getLinkPadding());
218  cenv_->setLinkScale(src.getCollisionEnv()->getLinkScale());
219 }
220 
221 void PlanningScene::allocateCollisionDetector(const collision_detection::CollisionDetectorAllocatorPtr& allocator,
222  const CollisionDetectorPtr& parent_detector)
223 {
224  // Temporarily keep pointer to the previous (if any) collision detector to copy padding from
225  CollisionDetectorPtr prev_coll_detector = collision_detector_;
226 
227  // Construct a fresh CollisionDetector and store allocator
228  collision_detector_ = std::make_shared<CollisionDetector>();
229  collision_detector_->alloc_ = allocator;
230 
231  // If parent_detector is specified, copy-construct collision environments (copies link shapes and attached objects)
232  // Otherwise, construct new collision environment from world and robot model
233  if (parent_detector)
234  {
235  collision_detector_->cenv_ = collision_detector_->alloc_->allocateEnv(parent_detector->cenv_, world_);
236  collision_detector_->cenv_unpadded_ =
237  collision_detector_->alloc_->allocateEnv(parent_detector->cenv_unpadded_, world_);
238  }
239  else
240  {
241  collision_detector_->cenv_ = collision_detector_->alloc_->allocateEnv(world_, getRobotModel());
242  collision_detector_->cenv_unpadded_ = collision_detector_->alloc_->allocateEnv(world_, getRobotModel());
243 
244  // Copy padding to collision_detector_->cenv_
245  if (prev_coll_detector)
246  collision_detector_->copyPadding(*prev_coll_detector);
247  }
248 
249  // Assign const pointers
250  collision_detector_->cenv_const_ = collision_detector_->cenv_;
251  collision_detector_->cenv_unpadded_const_ = collision_detector_->cenv_unpadded_;
252 }
253 
254 const collision_detection::CollisionEnvConstPtr&
255 PlanningScene::getCollisionEnv(const std::string& collision_detector_name) const
256 {
257  if (collision_detector_name != getCollisionDetectorName())
258  {
259  RCLCPP_ERROR(LOGGER, "Could not get CollisionRobot named '%s'. Returning active CollisionRobot '%s' instead",
260  collision_detector_name.c_str(), collision_detector_->alloc_->getName().c_str());
261  return collision_detector_->getCollisionEnv();
262  }
263 
264  return collision_detector_->getCollisionEnv();
265 }
266 
267 const collision_detection::CollisionEnvConstPtr&
268 PlanningScene::getCollisionEnvUnpadded(const std::string& collision_detector_name) const
269 {
270  if (collision_detector_name != getCollisionDetectorName())
271  {
272  RCLCPP_ERROR(LOGGER,
273  "Could not get CollisionRobotUnpadded named '%s'. "
274  "Returning active CollisionRobotUnpadded '%s' instead",
275  collision_detector_name.c_str(), collision_detector_->alloc_->getName().c_str());
276  return collision_detector_->getCollisionEnvUnpadded();
277  }
278 
279  return collision_detector_->getCollisionEnvUnpadded();
280 }
281 
283 {
284  if (!parent_)
285  return;
286 
287  // clear everything, reset the world, record diffs
288  world_ = std::make_shared<collision_detection::World>(*parent_->world_);
289  world_const_ = world_;
290  world_diff_ = std::make_shared<collision_detection::WorldDiff>(world_);
291  if (current_world_object_update_callback_)
292  current_world_object_update_observer_handle_ = world_->addObserver(current_world_object_update_callback_);
293 
294  // Reset collision detector to the the parent's version
295  allocateCollisionDetector(parent_->collision_detector_->alloc_, parent_->collision_detector_);
296 
297  scene_transforms_.reset();
298  robot_state_.reset();
299  acm_.reset();
300  object_colors_.reset();
301  object_types_.reset();
302 }
303 
304 void PlanningScene::pushDiffs(const PlanningScenePtr& scene)
305 {
306  if (!parent_)
307  return;
308 
309  if (scene_transforms_)
310  scene->getTransformsNonConst().setAllTransforms(scene_transforms_->getAllTransforms());
311 
312  if (robot_state_)
313  {
314  scene->getCurrentStateNonConst() = *robot_state_;
315  // push colors and types for attached objects
316  std::vector<const moveit::core::AttachedBody*> attached_objs;
317  robot_state_->getAttachedBodies(attached_objs);
318  for (const moveit::core::AttachedBody* attached_obj : attached_objs)
319  {
320  if (hasObjectType(attached_obj->getName()))
321  scene->setObjectType(attached_obj->getName(), getObjectType(attached_obj->getName()));
322  if (hasObjectColor(attached_obj->getName()))
323  scene->setObjectColor(attached_obj->getName(), getObjectColor(attached_obj->getName()));
324  }
325  }
326 
327  if (acm_)
328  scene->getAllowedCollisionMatrixNonConst() = *acm_;
329 
330  collision_detection::CollisionEnvPtr active_cenv = scene->getCollisionEnvNonConst();
331  active_cenv->setLinkPadding(collision_detector_->cenv_->getLinkPadding());
332  active_cenv->setLinkScale(collision_detector_->cenv_->getLinkScale());
333 
334  if (world_diff_)
335  {
336  for (const std::pair<const std::string, collision_detection::World::Action>& it : *world_diff_)
337  {
338  if (it.second == collision_detection::World::DESTROY)
339  {
340  scene->world_->removeObject(it.first);
341  scene->removeObjectColor(it.first);
342  scene->removeObjectType(it.first);
343  }
344  else
345  {
346  const collision_detection::World::Object& obj = *world_->getObject(it.first);
347  scene->world_->removeObject(obj.id_);
348  scene->world_->addToObject(obj.id_, obj.pose_, obj.shapes_, obj.shape_poses_);
349  if (hasObjectColor(it.first))
350  scene->setObjectColor(it.first, getObjectColor(it.first));
351  if (hasObjectType(it.first))
352  scene->setObjectType(it.first, getObjectType(it.first));
353 
354  scene->world_->setSubframesOfObject(obj.id_, obj.subframe_poses_);
355  }
356  }
357  }
358 }
359 
362 {
363  if (getCurrentState().dirtyCollisionBodyTransforms())
365  else
366  checkCollision(req, res, getCurrentState());
367 }
368 
371  const moveit::core::RobotState& robot_state) const
372 {
373  checkCollision(req, res, robot_state, getAllowedCollisionMatrix());
374 }
375 
378 {
379  if (getCurrentState().dirtyCollisionBodyTransforms())
381  else
382  checkSelfCollision(req, res, getCurrentState());
383 }
384 
387  const moveit::core::RobotState& robot_state,
389 {
390  // check collision with the world using the padded version
391  getCollisionEnv()->checkRobotCollision(req, res, robot_state, acm);
392 
393  // do self-collision checking with the unpadded version of the robot
394  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
395  getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm);
396 }
397 
400 {
401  if (getCurrentState().dirtyCollisionBodyTransforms())
403  else
405 }
406 
409  const moveit::core::RobotState& robot_state,
411 {
412  // check collision with the world using the unpadded version
413  getCollisionEnvUnpadded()->checkRobotCollision(req, res, robot_state, acm);
414 
415  // do self-collision checking with the unpadded version of the robot
416  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
417  {
418  getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm);
419  }
420 }
421 
423 {
424  if (getCurrentState().dirtyCollisionBodyTransforms())
426  else
428 }
429 
431  const moveit::core::RobotState& robot_state,
433  const std::string& group_name) const
434 {
436  req.contacts = true;
437  req.max_contacts = getRobotModel()->getLinkModelsWithCollisionGeometry().size() + 1;
438  req.max_contacts_per_pair = 1;
439  req.group_name = group_name;
441  checkCollision(req, res, robot_state, acm);
442  res.contacts.swap(contacts);
443 }
444 
445 void PlanningScene::getCollidingLinks(std::vector<std::string>& links)
446 {
447  if (getCurrentState().dirtyCollisionBodyTransforms())
449  else
451 }
452 
453 void PlanningScene::getCollidingLinks(std::vector<std::string>& links, const moveit::core::RobotState& robot_state,
455 {
457  getCollidingPairs(contacts, robot_state, acm);
458  links.clear();
459  for (collision_detection::CollisionResult::ContactMap::const_iterator it = contacts.begin(); it != contacts.end();
460  ++it)
461  for (const collision_detection::Contact& contact : it->second)
462  {
464  links.push_back(contact.body_name_1);
466  links.push_back(contact.body_name_2);
467  }
468 }
469 
470 const collision_detection::CollisionEnvPtr& PlanningScene::getCollisionEnvNonConst()
471 {
472  return collision_detector_->cenv_;
473 }
474 
476 {
477  if (!robot_state_)
478  {
479  robot_state_ = std::make_shared<moveit::core::RobotState>(parent_->getCurrentState());
480  robot_state_->setAttachedBodyUpdateCallback(current_state_attached_body_callback_);
481  }
482  robot_state_->update();
483  return *robot_state_;
484 }
485 
486 moveit::core::RobotStatePtr PlanningScene::getCurrentStateUpdated(const moveit_msgs::msg::RobotState& update) const
487 {
488  auto state = std::make_shared<moveit::core::RobotState>(getCurrentState());
490  return state;
491 }
492 
494 {
495  current_state_attached_body_callback_ = callback;
496  if (robot_state_)
497  robot_state_->setAttachedBodyUpdateCallback(callback);
498 }
499 
501 {
502  if (current_world_object_update_callback_)
503  world_->removeObserver(current_world_object_update_observer_handle_);
504  if (callback)
505  current_world_object_update_observer_handle_ = world_->addObserver(callback);
506  current_world_object_update_callback_ = callback;
507 }
508 
510 {
511  if (!acm_)
512  acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(parent_->getAllowedCollisionMatrix());
513  return *acm_;
514 }
515 
517 {
518  // Trigger an update of the robot transforms
520  return static_cast<const PlanningScene*>(this)->getTransforms();
521 }
522 
524 {
525  // Trigger an update of the robot transforms
527  if (!scene_transforms_)
528  {
529  // The only case when there are no transforms is if this planning scene has a parent. When a non-const version of
530  // the planning scene is requested, a copy of the parent's transforms is forced
531  scene_transforms_ = std::make_shared<SceneTransforms>(this);
532  scene_transforms_->setAllTransforms(parent_->getTransforms().getAllTransforms());
533  }
534  return *scene_transforms_;
535 }
536 
537 void PlanningScene::getPlanningSceneDiffMsg(moveit_msgs::msg::PlanningScene& scene_msg) const
538 {
539  scene_msg.name = name_;
540  scene_msg.robot_model_name = getRobotModel()->getName();
541  scene_msg.is_diff = true;
542 
543  if (scene_transforms_)
544  scene_transforms_->copyTransforms(scene_msg.fixed_frame_transforms);
545  else
546  scene_msg.fixed_frame_transforms.clear();
547 
548  if (robot_state_)
549  moveit::core::robotStateToRobotStateMsg(*robot_state_, scene_msg.robot_state);
550  else
551  {
552  scene_msg.robot_state = moveit_msgs::msg::RobotState();
553  }
554  scene_msg.robot_state.is_diff = true;
555 
556  if (acm_)
557  acm_->getMessage(scene_msg.allowed_collision_matrix);
558  else
559  scene_msg.allowed_collision_matrix = moveit_msgs::msg::AllowedCollisionMatrix();
560 
561  collision_detector_->cenv_->getPadding(scene_msg.link_padding);
562  collision_detector_->cenv_->getScale(scene_msg.link_scale);
563 
564  scene_msg.object_colors.clear();
565  if (object_colors_)
566  {
567  unsigned int i = 0;
568  scene_msg.object_colors.resize(object_colors_->size());
569  for (ObjectColorMap::const_iterator it = object_colors_->begin(); it != object_colors_->end(); ++it, ++i)
570  {
571  scene_msg.object_colors[i].id = it->first;
572  scene_msg.object_colors[i].color = it->second;
573  }
574  }
575 
576  scene_msg.world.collision_objects.clear();
577  scene_msg.world.octomap = octomap_msgs::msg::OctomapWithPose();
578 
579  if (world_diff_)
580  {
581  bool do_omap = false;
582  for (const std::pair<const std::string, collision_detection::World::Action>& it : *world_diff_)
583  {
584  if (it.first == OCTOMAP_NS)
585  do_omap = true;
586  else if (it.second == collision_detection::World::DESTROY)
587  {
588  // if object became attached, it should not be recorded as removed here
589  if (!std::count_if(scene_msg.robot_state.attached_collision_objects.cbegin(),
590  scene_msg.robot_state.attached_collision_objects.cend(),
591  [&it](const moveit_msgs::msg::AttachedCollisionObject& aco) {
592  return aco.object.id == it.first &&
593  aco.object.operation == moveit_msgs::msg::CollisionObject::ADD;
594  }))
595  {
596  moveit_msgs::msg::CollisionObject co;
597  co.header.frame_id = getPlanningFrame();
598  co.id = it.first;
599  co.operation = moveit_msgs::msg::CollisionObject::REMOVE;
600  scene_msg.world.collision_objects.push_back(co);
601  }
602  }
603  else
604  {
605  scene_msg.world.collision_objects.emplace_back();
606  getCollisionObjectMsg(scene_msg.world.collision_objects.back(), it.first);
607  }
608  }
609  if (do_omap)
610  getOctomapMsg(scene_msg.world.octomap);
611  }
612 
613  // Ensure all detached collision objects actually get removed when applying the diff
614  // Because RobotState doesn't handle diffs (yet), we explicitly declare attached objects
615  // as removed, if they show up as "normal" collision objects but were attached in parent
616  for (const auto& collision_object : scene_msg.world.collision_objects)
617  {
618  if (parent_ && parent_->getCurrentState().hasAttachedBody(collision_object.id))
619  {
620  moveit_msgs::msg::AttachedCollisionObject aco;
621  aco.object.id = collision_object.id;
622  aco.object.operation = moveit_msgs::msg::CollisionObject::REMOVE;
623  scene_msg.robot_state.attached_collision_objects.push_back(aco);
624  }
625  }
626 }
627 
628 namespace
629 {
630 class ShapeVisitorAddToCollisionObject : public boost::static_visitor<void>
631 {
632 public:
633  ShapeVisitorAddToCollisionObject(moveit_msgs::msg::CollisionObject* obj) : boost::static_visitor<void>(), obj_(obj)
634  {
635  }
636 
637  void setPoseMessage(const geometry_msgs::msg::Pose* pose)
638  {
639  pose_ = pose;
640  }
641 
642  void operator()(const shape_msgs::msg::Plane& shape_msg) const
643  {
644  obj_->planes.push_back(shape_msg);
645  obj_->plane_poses.push_back(*pose_);
646  }
647 
648  void operator()(const shape_msgs::msg::Mesh& shape_msg) const
649  {
650  obj_->meshes.push_back(shape_msg);
651  obj_->mesh_poses.push_back(*pose_);
652  }
653 
654  void operator()(const shape_msgs::msg::SolidPrimitive& shape_msg) const
655  {
656  obj_->primitives.push_back(shape_msg);
657  obj_->primitive_poses.push_back(*pose_);
658  }
659 
660 private:
661  moveit_msgs::msg::CollisionObject* obj_;
662  const geometry_msgs::msg::Pose* pose_;
663 };
664 } // namespace
665 
666 bool PlanningScene::getCollisionObjectMsg(moveit_msgs::msg::CollisionObject& collision_obj, const std::string& ns) const
667 {
668  collision_detection::CollisionEnv::ObjectConstPtr obj = world_->getObject(ns);
669  if (!obj)
670  return false;
671  collision_obj.header.frame_id = getPlanningFrame();
672  collision_obj.pose = tf2::toMsg(obj->pose_);
673  collision_obj.id = ns;
674  collision_obj.operation = moveit_msgs::msg::CollisionObject::ADD;
675 
676  ShapeVisitorAddToCollisionObject sv(&collision_obj);
677  for (std::size_t j = 0; j < obj->shapes_.size(); ++j)
678  {
679  shapes::ShapeMsg sm;
680  if (constructMsgFromShape(obj->shapes_[j].get(), sm))
681  {
682  geometry_msgs::msg::Pose p = tf2::toMsg(obj->shape_poses_[j]);
683  sv.setPoseMessage(&p);
684  boost::apply_visitor(sv, sm);
685  }
686  }
687 
688  if (!collision_obj.primitives.empty() || !collision_obj.meshes.empty() || !collision_obj.planes.empty())
689  {
690  if (hasObjectType(collision_obj.id))
691  collision_obj.type = getObjectType(collision_obj.id);
692  }
693  for (const auto& frame_pair : obj->subframe_poses_)
694  {
695  collision_obj.subframe_names.push_back(frame_pair.first);
696  geometry_msgs::msg::Pose p;
697  p = tf2::toMsg(frame_pair.second);
698  collision_obj.subframe_poses.push_back(p);
699  }
700 
701  return true;
702 }
703 
704 void PlanningScene::getCollisionObjectMsgs(std::vector<moveit_msgs::msg::CollisionObject>& collision_objs) const
705 {
706  collision_objs.clear();
707  const std::vector<std::string>& ids = world_->getObjectIds();
708  for (const std::string& id : ids)
709  if (id != OCTOMAP_NS)
710  {
711  collision_objs.emplace_back();
712  getCollisionObjectMsg(collision_objs.back(), id);
713  }
714 }
715 
716 bool PlanningScene::getAttachedCollisionObjectMsg(moveit_msgs::msg::AttachedCollisionObject& attached_collision_obj,
717  const std::string& ns) const
718 {
719  std::vector<moveit_msgs::msg::AttachedCollisionObject> attached_collision_objs;
720  getAttachedCollisionObjectMsgs(attached_collision_objs);
721  for (moveit_msgs::msg::AttachedCollisionObject& it : attached_collision_objs)
722  {
723  if (it.object.id == ns)
724  {
725  attached_collision_obj = it;
726  return true;
727  }
728  }
729  return false;
730 }
731 
733  std::vector<moveit_msgs::msg::AttachedCollisionObject>& attached_collision_objs) const
734 {
735  std::vector<const moveit::core::AttachedBody*> attached_bodies;
736  getCurrentState().getAttachedBodies(attached_bodies);
737  attachedBodiesToAttachedCollisionObjectMsgs(attached_bodies, attached_collision_objs);
738 }
739 
740 bool PlanningScene::getOctomapMsg(octomap_msgs::msg::OctomapWithPose& octomap) const
741 {
742  octomap.header.frame_id = getPlanningFrame();
743  octomap.octomap = octomap_msgs::msg::Octomap();
744 
746  if (map)
747  {
748  if (map->shapes_.size() == 1)
749  {
750  const shapes::OcTree* o = static_cast<const shapes::OcTree*>(map->shapes_[0].get());
751  octomap_msgs::fullMapToMsg(*o->octree, octomap.octomap);
752  octomap.origin = tf2::toMsg(map->shape_poses_[0]);
753  return true;
754  }
755  RCLCPP_ERROR(LOGGER, "Unexpected number of shapes in octomap collision object. Not including '%s' object",
756  OCTOMAP_NS.c_str());
757  }
758  return false;
759 }
760 
761 void PlanningScene::getObjectColorMsgs(std::vector<moveit_msgs::msg::ObjectColor>& object_colors) const
762 {
763  object_colors.clear();
764 
765  unsigned int i = 0;
766  ObjectColorMap cmap;
767  getKnownObjectColors(cmap);
768  object_colors.resize(cmap.size());
769  for (ObjectColorMap::const_iterator it = cmap.begin(); it != cmap.end(); ++it, ++i)
770  {
771  object_colors[i].id = it->first;
772  object_colors[i].color = it->second;
773  }
774 }
775 
776 void PlanningScene::getPlanningSceneMsg(moveit_msgs::msg::PlanningScene& scene_msg) const
777 {
778  scene_msg.name = name_;
779  scene_msg.is_diff = false;
780  scene_msg.robot_model_name = getRobotModel()->getName();
781  getTransforms().copyTransforms(scene_msg.fixed_frame_transforms);
782 
784  getAllowedCollisionMatrix().getMessage(scene_msg.allowed_collision_matrix);
785  getCollisionEnv()->getPadding(scene_msg.link_padding);
786  getCollisionEnv()->getScale(scene_msg.link_scale);
787 
788  getObjectColorMsgs(scene_msg.object_colors);
789 
790  // add collision objects
791  getCollisionObjectMsgs(scene_msg.world.collision_objects);
792 
793  // get the octomap
794  getOctomapMsg(scene_msg.world.octomap);
795 }
796 
797 void PlanningScene::getPlanningSceneMsg(moveit_msgs::msg::PlanningScene& scene_msg,
798  const moveit_msgs::msg::PlanningSceneComponents& comp) const
799 {
800  scene_msg.is_diff = false;
801  if (comp.components & moveit_msgs::msg::PlanningSceneComponents::SCENE_SETTINGS)
802  {
803  scene_msg.name = name_;
804  scene_msg.robot_model_name = getRobotModel()->getName();
805  }
806 
807  if (comp.components & moveit_msgs::msg::PlanningSceneComponents::TRANSFORMS)
808  getTransforms().copyTransforms(scene_msg.fixed_frame_transforms);
809 
810  if (comp.components & moveit_msgs::msg::PlanningSceneComponents::ROBOT_STATE_ATTACHED_OBJECTS)
811  {
812  moveit::core::robotStateToRobotStateMsg(getCurrentState(), scene_msg.robot_state, true);
813  for (moveit_msgs::msg::AttachedCollisionObject& attached_collision_object :
814  scene_msg.robot_state.attached_collision_objects)
815  {
816  if (hasObjectType(attached_collision_object.object.id))
817  {
818  attached_collision_object.object.type = getObjectType(attached_collision_object.object.id);
819  }
820  }
821  }
822  else if (comp.components & moveit_msgs::msg::PlanningSceneComponents::ROBOT_STATE)
823  {
824  moveit::core::robotStateToRobotStateMsg(getCurrentState(), scene_msg.robot_state, false);
825  }
826 
827  if (comp.components & moveit_msgs::msg::PlanningSceneComponents::ALLOWED_COLLISION_MATRIX)
828  getAllowedCollisionMatrix().getMessage(scene_msg.allowed_collision_matrix);
829 
830  if (comp.components & moveit_msgs::msg::PlanningSceneComponents::LINK_PADDING_AND_SCALING)
831  {
832  getCollisionEnv()->getPadding(scene_msg.link_padding);
833  getCollisionEnv()->getScale(scene_msg.link_scale);
834  }
835 
836  if (comp.components & moveit_msgs::msg::PlanningSceneComponents::OBJECT_COLORS)
837  getObjectColorMsgs(scene_msg.object_colors);
838 
839  // add collision objects
840  if (comp.components & moveit_msgs::msg::PlanningSceneComponents::WORLD_OBJECT_GEOMETRY)
841  getCollisionObjectMsgs(scene_msg.world.collision_objects);
842  else if (comp.components & moveit_msgs::msg::PlanningSceneComponents::WORLD_OBJECT_NAMES)
843  {
844  const std::vector<std::string>& ids = world_->getObjectIds();
845  scene_msg.world.collision_objects.clear();
846  scene_msg.world.collision_objects.reserve(ids.size());
847  for (const std::string& id : ids)
848  if (id != OCTOMAP_NS)
849  {
850  moveit_msgs::msg::CollisionObject co;
851  co.id = id;
852  if (hasObjectType(co.id))
853  co.type = getObjectType(co.id);
854  scene_msg.world.collision_objects.push_back(co);
855  }
856  }
857 
858  // get the octomap
859  if (comp.components & moveit_msgs::msg::PlanningSceneComponents::OCTOMAP)
860  getOctomapMsg(scene_msg.world.octomap);
861 }
862 
863 void PlanningScene::saveGeometryToStream(std::ostream& out) const
864 {
865  out << name_ << '\n';
866  const std::vector<std::string>& ids = world_->getObjectIds();
867  for (const std::string& id : ids)
868  if (id != OCTOMAP_NS)
869  {
870  collision_detection::CollisionEnv::ObjectConstPtr obj = world_->getObject(id);
871  if (obj)
872  {
873  out << "* " << id << '\n'; // New object start
874  // Write object pose
875  writePoseToText(out, obj->pose_);
876 
877  // Write shapes and shape poses
878  out << obj->shapes_.size() << '\n'; // Number of shapes
879  for (std::size_t j = 0; j < obj->shapes_.size(); ++j)
880  {
881  shapes::saveAsText(obj->shapes_[j].get(), out);
882  // shape_poses_ is valid isometry by contract
883  writePoseToText(out, obj->shape_poses_[j]);
884  if (hasObjectColor(id))
885  {
886  const std_msgs::msg::ColorRGBA& c = getObjectColor(id);
887  out << c.r << " " << c.g << " " << c.b << " " << c.a << '\n';
888  }
889  else
890  out << "0 0 0 0" << '\n';
891  }
892 
893  // Write subframes
894  out << obj->subframe_poses_.size() << '\n'; // Number of subframes
895  for (auto& pose_pair : obj->subframe_poses_)
896  {
897  out << pose_pair.first << '\n'; // Subframe name
898  writePoseToText(out, pose_pair.second); // Subframe pose
899  }
900  }
901  }
902  out << "." << '\n';
903 }
904 
906 {
907  return loadGeometryFromStream(in, Eigen::Isometry3d::Identity()); // Use no offset
908 }
909 
910 bool PlanningScene::loadGeometryFromStream(std::istream& in, const Eigen::Isometry3d& offset)
911 {
912  if (!in.good() || in.eof())
913  {
914  RCLCPP_ERROR(LOGGER, "Bad input stream when loading scene geometry");
915  return false;
916  }
917  // Read scene name
918  std::getline(in, name_);
919 
920  // Identify scene format version for backwards compatibility of parser
921  auto pos = in.tellg(); // remember current stream position
922  std::string line;
923  do
924  {
925  std::getline(in, line);
926  } while (in.good() && !in.eof() && (line.empty() || line[0] != '*')); // read * marker
927  std::getline(in, line); // next line determines format
928  boost::algorithm::trim(line);
929  // new format: line specifies position of object, with spaces as delimiter -> spaces indicate new format
930  // old format: line specifies number of shapes
931  bool uses_new_scene_format = line.find(' ') != std::string::npos;
932  in.seekg(pos);
933 
934  Eigen::Isometry3d pose; // Transient
935  do
936  {
937  std::string marker;
938  in >> marker;
939  if (!in.good() || in.eof())
940  {
941  RCLCPP_ERROR(LOGGER, "Bad input stream when loading marker in scene geometry");
942  return false;
943  }
944  if (marker == "*") // Start of new object
945  {
946  std::string object_id;
947  std::getline(in, object_id);
948  if (!in.good() || in.eof())
949  {
950  RCLCPP_ERROR(LOGGER, "Bad input stream when loading object_id in scene geometry");
951  return false;
952  }
953  boost::algorithm::trim(object_id);
954 
955  // Read in object pose (added in the new scene format)
956  pose.setIdentity();
957  if (uses_new_scene_format && !readPoseFromText(in, pose))
958  {
959  RCLCPP_ERROR(LOGGER, "Failed to read object pose from scene file");
960  return false;
961  }
962  pose = offset * pose; // Transform pose by input pose offset
963  world_->setObjectPose(object_id, pose);
964 
965  // Read in shapes
966  unsigned int shape_count;
967  in >> shape_count;
968  for (std::size_t i = 0; i < shape_count && in.good() && !in.eof(); ++i)
969  {
970  const auto shape = shapes::ShapeConstPtr(shapes::constructShapeFromText(in));
971  if (!shape)
972  {
973  RCLCPP_ERROR(LOGGER, "Failed to load shape from scene file");
974  return false;
975  }
976  if (!readPoseFromText(in, pose))
977  {
978  RCLCPP_ERROR(LOGGER, "Failed to read pose from scene file");
979  return false;
980  }
981  float r, g, b, a;
982  if (!(in >> r >> g >> b >> a))
983  {
984  RCLCPP_ERROR(LOGGER, "Improperly formatted color in scene geometry file");
985  return false;
986  }
987  if (shape)
988  {
989  world_->addToObject(object_id, shape, pose);
990  if (r > 0.0f || g > 0.0f || b > 0.0f || a > 0.0f)
991  {
992  std_msgs::msg::ColorRGBA color;
993  color.r = r;
994  color.g = g;
995  color.b = b;
996  color.a = a;
997  setObjectColor(object_id, color);
998  }
999  }
1000  }
1001 
1002  // Read in subframes (added in the new scene format)
1003  if (uses_new_scene_format)
1004  {
1006  unsigned int subframe_count;
1007  in >> subframe_count;
1008  for (std::size_t i = 0; i < subframe_count && in.good() && !in.eof(); ++i)
1009  {
1010  std::string subframe_name;
1011  in >> subframe_name;
1012  if (!readPoseFromText(in, pose))
1013  {
1014  RCLCPP_ERROR(LOGGER, "Failed to read subframe pose from scene file");
1015  return false;
1016  }
1017  subframes[subframe_name] = pose;
1018  }
1019  world_->setSubframesOfObject(object_id, subframes);
1020  }
1021  }
1022  else if (marker == ".")
1023  {
1024  // Marks the end of the scene geometry;
1025  return true;
1026  }
1027  else
1028  {
1029  RCLCPP_ERROR(LOGGER, "Unknown marker in scene geometry file: %s ", marker.c_str());
1030  return false;
1031  }
1032  } while (true);
1033 }
1034 
1035 bool PlanningScene::readPoseFromText(std::istream& in, Eigen::Isometry3d& pose) const
1036 {
1037  double x, y, z, rx, ry, rz, rw;
1038  if (!(in >> x >> y >> z))
1039  {
1040  RCLCPP_ERROR(LOGGER, "Improperly formatted translation in scene geometry file");
1041  return false;
1042  }
1043  if (!(in >> rx >> ry >> rz >> rw))
1044  {
1045  RCLCPP_ERROR(LOGGER, "Improperly formatted rotation in scene geometry file");
1046  return false;
1047  }
1048  pose = Eigen::Translation3d(x, y, z) * Eigen::Quaterniond(rw, rx, ry, rz);
1049  return true;
1050 }
1051 
1052 void PlanningScene::writePoseToText(std::ostream& out, const Eigen::Isometry3d& pose) const
1053 {
1054  out << pose.translation().x() << " " << pose.translation().y() << " " << pose.translation().z() << '\n';
1055  Eigen::Quaterniond r(pose.linear());
1056  out << r.x() << " " << r.y() << " " << r.z() << " " << r.w() << '\n';
1057 }
1058 
1059 void PlanningScene::setCurrentState(const moveit_msgs::msg::RobotState& state)
1060 {
1061  // The attached bodies will be processed separately by processAttachedCollisionObjectMsgs
1062  // after robot_state_ has been updated
1063  moveit_msgs::msg::RobotState state_no_attached(state);
1064  state_no_attached.attached_collision_objects.clear();
1065 
1066  if (parent_)
1067  {
1068  if (!robot_state_)
1069  {
1070  robot_state_ = std::make_shared<moveit::core::RobotState>(parent_->getCurrentState());
1071  robot_state_->setAttachedBodyUpdateCallback(current_state_attached_body_callback_);
1072  }
1073  moveit::core::robotStateMsgToRobotState(getTransforms(), state_no_attached, *robot_state_);
1074  }
1075  else
1076  moveit::core::robotStateMsgToRobotState(*scene_transforms_, state_no_attached, *robot_state_);
1077 
1078  for (std::size_t i = 0; i < state.attached_collision_objects.size(); ++i)
1079  {
1080  if (!state.is_diff && state.attached_collision_objects[i].object.operation != moveit_msgs::msg::CollisionObject::ADD)
1081  {
1082  RCLCPP_ERROR(LOGGER,
1083  "The specified RobotState is not marked as is_diff. "
1084  "The request to modify the object '%s' is not supported. Object is ignored.",
1085  state.attached_collision_objects[i].object.id.c_str());
1086  continue;
1087  }
1088  processAttachedCollisionObjectMsg(state.attached_collision_objects[i]);
1089  }
1090 }
1091 
1093 {
1094  getCurrentStateNonConst() = state;
1095 }
1096 
1098 {
1099  if (!parent_)
1100  return;
1101 
1102  // This child planning scene did not have its own copy of frame transforms
1103  if (!scene_transforms_)
1104  {
1105  scene_transforms_ = std::make_shared<SceneTransforms>(this);
1106  scene_transforms_->setAllTransforms(parent_->getTransforms().getAllTransforms());
1107  }
1108 
1109  if (!robot_state_)
1110  {
1111  robot_state_ = std::make_shared<moveit::core::RobotState>(parent_->getCurrentState());
1112  robot_state_->setAttachedBodyUpdateCallback(current_state_attached_body_callback_);
1113  }
1114 
1115  if (!acm_)
1116  acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(parent_->getAllowedCollisionMatrix());
1117 
1118  world_diff_.reset();
1119 
1120  if (!object_colors_)
1121  {
1122  ObjectColorMap kc;
1123  parent_->getKnownObjectColors(kc);
1124  object_colors_ = std::make_unique<ObjectColorMap>(kc);
1125  }
1126  else
1127  {
1128  ObjectColorMap kc;
1129  parent_->getKnownObjectColors(kc);
1130  for (ObjectColorMap::const_iterator it = kc.begin(); it != kc.end(); ++it)
1131  if (object_colors_->find(it->first) == object_colors_->end())
1132  (*object_colors_)[it->first] = it->second;
1133  }
1134 
1135  if (!object_types_)
1136  {
1137  ObjectTypeMap kc;
1138  parent_->getKnownObjectTypes(kc);
1139  object_types_ = std::make_unique<ObjectTypeMap>(kc);
1140  }
1141  else
1142  {
1143  ObjectTypeMap kc;
1144  parent_->getKnownObjectTypes(kc);
1145  for (ObjectTypeMap::const_iterator it = kc.begin(); it != kc.end(); ++it)
1146  if (object_types_->find(it->first) == object_types_->end())
1147  (*object_types_)[it->first] = it->second;
1148  }
1149 
1150  parent_.reset();
1151 }
1152 
1153 bool PlanningScene::setPlanningSceneDiffMsg(const moveit_msgs::msg::PlanningScene& scene_msg)
1154 {
1155  bool result = true;
1156 
1157  RCLCPP_DEBUG(LOGGER, "Adding planning scene diff");
1158  if (!scene_msg.name.empty())
1159  name_ = scene_msg.name;
1160 
1161  if (!scene_msg.robot_model_name.empty() && scene_msg.robot_model_name != getRobotModel()->getName())
1162  RCLCPP_WARN(LOGGER, "Setting the scene for model '%s' but model '%s' is loaded.",
1163  scene_msg.robot_model_name.c_str(), getRobotModel()->getName().c_str());
1164 
1165  // there is at least one transform in the list of fixed transform: from model frame to itself;
1166  // if the list is empty, then nothing has been set
1167  if (!scene_msg.fixed_frame_transforms.empty())
1168  {
1169  if (!scene_transforms_)
1170  scene_transforms_ = std::make_shared<SceneTransforms>(this);
1171  scene_transforms_->setTransforms(scene_msg.fixed_frame_transforms);
1172  }
1173 
1174  // if at least some joints have been specified, we set them
1175  if (!scene_msg.robot_state.multi_dof_joint_state.joint_names.empty() ||
1176  !scene_msg.robot_state.joint_state.name.empty() || !scene_msg.robot_state.attached_collision_objects.empty())
1177  setCurrentState(scene_msg.robot_state);
1178 
1179  // if at least some links are mentioned in the allowed collision matrix, then we have an update
1180  if (!scene_msg.allowed_collision_matrix.entry_names.empty())
1181  acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(scene_msg.allowed_collision_matrix);
1182 
1183  if (!scene_msg.link_padding.empty() || !scene_msg.link_scale.empty())
1184  {
1185  collision_detector_->cenv_->setPadding(scene_msg.link_padding);
1186  collision_detector_->cenv_->setScale(scene_msg.link_scale);
1187  }
1188 
1189  // if any colors have been specified, replace the ones we have with the specified ones
1190  for (const moveit_msgs::msg::ObjectColor& object_color : scene_msg.object_colors)
1191  setObjectColor(object_color.id, object_color.color);
1192 
1193  // process collision object updates
1194  for (const moveit_msgs::msg::CollisionObject& collision_object : scene_msg.world.collision_objects)
1195  result &= processCollisionObjectMsg(collision_object);
1196 
1197  // if an octomap was specified, replace the one we have with that one
1198  if (!scene_msg.world.octomap.octomap.data.empty())
1199  processOctomapMsg(scene_msg.world.octomap);
1200 
1201  return result;
1202 }
1203 
1204 bool PlanningScene::setPlanningSceneMsg(const moveit_msgs::msg::PlanningScene& scene_msg)
1205 {
1206  RCLCPP_DEBUG(LOGGER, "Setting new planning scene: '%s'", scene_msg.name.c_str());
1207  name_ = scene_msg.name;
1208 
1209  if (!scene_msg.robot_model_name.empty() && scene_msg.robot_model_name != getRobotModel()->getName())
1210  RCLCPP_WARN(LOGGER, "Setting the scene for model '%s' but model '%s' is loaded.",
1211  scene_msg.robot_model_name.c_str(), getRobotModel()->getName().c_str());
1212 
1213  if (parent_)
1214  decoupleParent();
1215 
1216  object_types_.reset();
1217  scene_transforms_->setTransforms(scene_msg.fixed_frame_transforms);
1218  setCurrentState(scene_msg.robot_state);
1219  acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(scene_msg.allowed_collision_matrix);
1220  collision_detector_->cenv_->setPadding(scene_msg.link_padding);
1221  collision_detector_->cenv_->setScale(scene_msg.link_scale);
1222  object_colors_ = std::make_unique<ObjectColorMap>();
1223  for (const moveit_msgs::msg::ObjectColor& object_color : scene_msg.object_colors)
1224  setObjectColor(object_color.id, object_color.color);
1225  world_->clearObjects();
1226  return processPlanningSceneWorldMsg(scene_msg.world);
1227 }
1228 
1229 bool PlanningScene::processPlanningSceneWorldMsg(const moveit_msgs::msg::PlanningSceneWorld& world)
1230 {
1231  bool result = true;
1232  for (const moveit_msgs::msg::CollisionObject& collision_object : world.collision_objects)
1233  result &= processCollisionObjectMsg(collision_object);
1234  processOctomapMsg(world.octomap);
1235  return result;
1236 }
1237 
1238 bool PlanningScene::usePlanningSceneMsg(const moveit_msgs::msg::PlanningScene& scene_msg)
1239 {
1240  if (scene_msg.is_diff)
1241  return setPlanningSceneDiffMsg(scene_msg);
1242  else
1243  return setPlanningSceneMsg(scene_msg);
1244 }
1245 
1246 collision_detection::OccMapTreePtr createOctomap(const octomap_msgs::msg::Octomap& map)
1247 {
1248  std::shared_ptr<collision_detection::OccMapTree> om =
1249  std::make_shared<collision_detection::OccMapTree>(map.resolution);
1250  if (map.binary)
1251  {
1252  octomap_msgs::readTree(om.get(), map);
1253  }
1254  else
1255  {
1256  std::stringstream datastream;
1257  if (!map.data.empty())
1258  {
1259  datastream.write((const char*)&map.data[0], map.data.size());
1260  om->readData(datastream);
1261  }
1262  }
1263  return om;
1264 }
1265 
1266 void PlanningScene::processOctomapMsg(const octomap_msgs::msg::Octomap& map)
1267 {
1268  // each octomap replaces any previous one
1269  world_->removeObject(OCTOMAP_NS);
1270 
1271  if (map.data.empty())
1272  return;
1273 
1274  if (map.id != "OcTree")
1275  {
1276  RCLCPP_ERROR(LOGGER, "Received octomap is of type '%s' but type 'OcTree' is expected.", map.id.c_str());
1277  return;
1278  }
1279 
1280  std::shared_ptr<collision_detection::OccMapTree> om = createOctomap(map);
1281  if (!map.header.frame_id.empty())
1282  {
1283  const Eigen::Isometry3d& t = getFrameTransform(map.header.frame_id);
1284  world_->addToObject(OCTOMAP_NS, std::make_shared<const shapes::OcTree>(om), t);
1285  }
1286  else
1287  {
1288  world_->addToObject(OCTOMAP_NS, std::make_shared<const shapes::OcTree>(om), Eigen::Isometry3d::Identity());
1289  }
1290 }
1291 
1293 {
1294  const std::vector<std::string>& object_ids = world_->getObjectIds();
1295  for (const std::string& object_id : object_ids)
1296  if (object_id != OCTOMAP_NS)
1297  {
1298  world_->removeObject(object_id);
1299  removeObjectColor(object_id);
1300  removeObjectType(object_id);
1301  }
1302 }
1303 
1304 void PlanningScene::processOctomapMsg(const octomap_msgs::msg::OctomapWithPose& map)
1305 {
1306  // each octomap replaces any previous one
1307  world_->removeObject(OCTOMAP_NS);
1308 
1309  if (map.octomap.data.empty())
1310  return;
1311 
1312  if (map.octomap.id != "OcTree")
1313  {
1314  RCLCPP_ERROR(LOGGER, "Received octomap is of type '%s' but type 'OcTree' is expected.", map.octomap.id.c_str());
1315  return;
1316  }
1317 
1318  std::shared_ptr<collision_detection::OccMapTree> om = createOctomap(map.octomap);
1319 
1320  const Eigen::Isometry3d& t = getFrameTransform(map.header.frame_id);
1321  Eigen::Isometry3d p;
1322  PlanningScene::poseMsgToEigen(map.origin, p);
1323  p = t * p;
1324  world_->addToObject(OCTOMAP_NS, std::make_shared<const shapes::OcTree>(om), p);
1325 }
1326 
1327 void PlanningScene::processOctomapPtr(const std::shared_ptr<const octomap::OcTree>& octree, const Eigen::Isometry3d& t)
1328 {
1330  if (map)
1331  {
1332  if (map->shapes_.size() == 1)
1333  {
1334  // check to see if we have the same octree pointer & pose.
1335  const shapes::OcTree* o = static_cast<const shapes::OcTree*>(map->shapes_[0].get());
1336  if (o->octree == octree)
1337  {
1338  // if the pose changed, we update it
1339  if (map->shape_poses_[0].isApprox(t, std::numeric_limits<double>::epsilon() * 100.0))
1340  {
1341  if (world_diff_)
1344  }
1345  else
1346  {
1347  shapes::ShapeConstPtr shape = map->shapes_[0];
1348  map.reset(); // reset this pointer first so that caching optimizations can be used in CollisionWorld
1349  world_->moveShapeInObject(OCTOMAP_NS, shape, t);
1350  }
1351  return;
1352  }
1353  }
1354  }
1355  // if the octree pointer changed, update the structure
1356  world_->removeObject(OCTOMAP_NS);
1357  world_->addToObject(OCTOMAP_NS, std::make_shared<const shapes::OcTree>(octree), t);
1358 }
1359 
1360 bool PlanningScene::processAttachedCollisionObjectMsg(const moveit_msgs::msg::AttachedCollisionObject& object)
1361 {
1362  if (object.object.operation == moveit_msgs::msg::CollisionObject::ADD &&
1363  !getRobotModel()->hasLinkModel(object.link_name))
1364  {
1365  RCLCPP_ERROR(LOGGER, "Unable to attach a body to link '%s' (link not found)", object.link_name.c_str());
1366  return false;
1367  }
1368 
1369  if (object.object.id == OCTOMAP_NS)
1370  {
1371  RCLCPP_ERROR(LOGGER, "The ID '%s' cannot be used for collision objects (name reserved)", OCTOMAP_NS.c_str());
1372  return false;
1373  }
1374 
1375  if (!robot_state_) // there must be a parent in this case
1376  {
1377  robot_state_ = std::make_shared<moveit::core::RobotState>(parent_->getCurrentState());
1378  robot_state_->setAttachedBodyUpdateCallback(current_state_attached_body_callback_);
1379  }
1380  robot_state_->update();
1381 
1382  // The ADD/REMOVE operations follow this order:
1383  // STEP 1: Get info about the object from either the message or the world/RobotState
1384  // STEP 2: Remove the object from the world/RobotState if necessary
1385  // STEP 3: Put the object in the RobotState/world
1386 
1387  if (object.object.operation == moveit_msgs::msg::CollisionObject::ADD ||
1388  object.object.operation == moveit_msgs::msg::CollisionObject::APPEND)
1389  {
1390  const moveit::core::LinkModel* link_model = getRobotModel()->getLinkModel(object.link_name);
1391  if (link_model)
1392  {
1393  // items to build the attached object from (filled from existing world object or message)
1394  Eigen::Isometry3d object_pose_in_link;
1395  std::vector<shapes::ShapeConstPtr> shapes;
1396  EigenSTL::vector_Isometry3d shape_poses;
1397  moveit::core::FixedTransformsMap subframe_poses;
1398 
1399  // STEP 1: Obtain info about object to be attached.
1400  // If it is in the world, message contents are ignored.
1401 
1402  collision_detection::CollisionEnv::ObjectConstPtr obj_in_world = world_->getObject(object.object.id);
1403  if (object.object.operation == moveit_msgs::msg::CollisionObject::ADD && object.object.primitives.empty() &&
1404  object.object.meshes.empty() && object.object.planes.empty())
1405  {
1406  if (obj_in_world)
1407  {
1408  RCLCPP_DEBUG(LOGGER, "Attaching world object '%s' to link '%s'", object.object.id.c_str(),
1409  object.link_name.c_str());
1410 
1411  object_pose_in_link = robot_state_->getGlobalLinkTransform(link_model).inverse() * obj_in_world->pose_;
1412  shapes = obj_in_world->shapes_;
1413  shape_poses = obj_in_world->shape_poses_;
1414  subframe_poses = obj_in_world->subframe_poses_;
1415  }
1416  else
1417  {
1418  RCLCPP_ERROR(LOGGER,
1419  "Attempting to attach object '%s' to link '%s' but no geometry specified "
1420  "and such an object does not exist in the collision world",
1421  object.object.id.c_str(), object.link_name.c_str());
1422  return false;
1423  }
1424  }
1425  else // If object is not in the world, use the message contents
1426  {
1427  Eigen::Isometry3d header_frame_to_object_pose;
1428  if (!shapesAndPosesFromCollisionObjectMessage(object.object, header_frame_to_object_pose, shapes, shape_poses))
1429  return false;
1430  const Eigen::Isometry3d world_to_header_frame = getFrameTransform(object.object.header.frame_id);
1431  const Eigen::Isometry3d link_to_header_frame =
1432  robot_state_->getGlobalLinkTransform(link_model).inverse() * world_to_header_frame;
1433  object_pose_in_link = link_to_header_frame * header_frame_to_object_pose;
1434 
1435  Eigen::Isometry3d subframe_pose;
1436  for (std::size_t i = 0; i < object.object.subframe_poses.size(); ++i)
1437  {
1438  PlanningScene::poseMsgToEigen(object.object.subframe_poses[i], subframe_pose);
1439  std::string name = object.object.subframe_names[i];
1440  subframe_poses[name] = subframe_pose;
1441  }
1442  }
1443 
1444  if (shapes.empty())
1445  {
1446  RCLCPP_ERROR(LOGGER, "There is no geometry to attach to link '%s' as part of attached body '%s'",
1447  object.link_name.c_str(), object.object.id.c_str());
1448  return false;
1449  }
1450 
1451  if (!object.object.type.db.empty() || !object.object.type.key.empty())
1452  setObjectType(object.object.id, object.object.type);
1453 
1454  // STEP 2: Remove the object from the world (if it existed)
1455  if (obj_in_world && world_->removeObject(object.object.id))
1456  {
1457  if (object.object.operation == moveit_msgs::msg::CollisionObject::ADD)
1458  RCLCPP_DEBUG(LOGGER, "Removing world object with the same name as newly attached object: '%s'",
1459  object.object.id.c_str());
1460  else
1461  RCLCPP_WARN(LOGGER,
1462  "You tried to append geometry to an attached object "
1463  "that is actually a world object ('%s'). World geometry is ignored.",
1464  object.object.id.c_str());
1465  }
1466 
1467  // STEP 3: Attach the object to the robot
1468  if (object.object.operation == moveit_msgs::msg::CollisionObject::ADD ||
1469  !robot_state_->hasAttachedBody(object.object.id))
1470  {
1471  if (robot_state_->clearAttachedBody(object.object.id))
1472  RCLCPP_DEBUG(LOGGER,
1473  "The robot state already had an object named '%s' attached to link '%s'. "
1474  "The object was replaced.",
1475  object.object.id.c_str(), object.link_name.c_str());
1476  robot_state_->attachBody(object.object.id, object_pose_in_link, shapes, shape_poses, object.touch_links,
1477  object.link_name, object.detach_posture, subframe_poses);
1478  RCLCPP_DEBUG(LOGGER, "Attached object '%s' to link '%s'", object.object.id.c_str(), object.link_name.c_str());
1479  }
1480  else // APPEND: augment to existing attached object
1481  {
1482  const moveit::core::AttachedBody* ab = robot_state_->getAttachedBody(object.object.id);
1483 
1484  // Allow overriding the body's pose if provided, otherwise keep the old one
1485  if (moveit::core::isEmpty(object.object.pose))
1486  object_pose_in_link = ab->getPose(); // Keep old pose
1487 
1488  shapes.insert(shapes.end(), ab->getShapes().begin(), ab->getShapes().end());
1489  shape_poses.insert(shape_poses.end(), ab->getShapePoses().begin(), ab->getShapePoses().end());
1490  subframe_poses.insert(ab->getSubframes().begin(), ab->getSubframes().end());
1491  trajectory_msgs::msg::JointTrajectory detach_posture =
1492  object.detach_posture.joint_names.empty() ? ab->getDetachPosture() : object.detach_posture;
1493 
1494  std::set<std::string> touch_links = ab->getTouchLinks();
1495  touch_links.insert(std::make_move_iterator(object.touch_links.begin()),
1496  std::make_move_iterator(object.touch_links.end()));
1497 
1498  robot_state_->clearAttachedBody(object.object.id);
1499  robot_state_->attachBody(object.object.id, object_pose_in_link, shapes, shape_poses, touch_links,
1500  object.link_name, detach_posture, subframe_poses);
1501  RCLCPP_DEBUG(LOGGER, "Appended things to object '%s' attached to link '%s'", object.object.id.c_str(),
1502  object.link_name.c_str());
1503  }
1504  return true;
1505  }
1506  else
1507  {
1508  RCLCPP_ERROR(LOGGER, "Robot state is not compatible with robot model. This could be fatal.");
1509  }
1510  }
1511  else if (object.object.operation == moveit_msgs::msg::CollisionObject::REMOVE) // == DETACH
1512  {
1513  // STEP 1: Get info about the object from the RobotState
1514  std::vector<const moveit::core::AttachedBody*> attached_bodies;
1515  if (object.object.id.empty())
1516  {
1517  const moveit::core::LinkModel* link_model =
1518  object.link_name.empty() ? nullptr : getRobotModel()->getLinkModel(object.link_name);
1519  if (link_model) // if we have a link model specified, only fetch bodies attached to this link
1520  robot_state_->getAttachedBodies(attached_bodies, link_model);
1521  else
1522  robot_state_->getAttachedBodies(attached_bodies);
1523  }
1524  else // A specific object id will be removed.
1525  {
1526  const moveit::core::AttachedBody* body = robot_state_->getAttachedBody(object.object.id);
1527  if (body)
1528  {
1529  if (!object.link_name.empty() && (body->getAttachedLinkName() != object.link_name))
1530  {
1531  RCLCPP_ERROR_STREAM(LOGGER, "The AttachedCollisionObject message states the object is attached to "
1532  << object.link_name << ", but it is actually attached to "
1533  << body->getAttachedLinkName()
1534  << ". Leave the link_name empty or specify the correct link.");
1535  return false;
1536  }
1537  attached_bodies.push_back(body);
1538  }
1539  }
1540 
1541  // STEP 2+3: Remove the attached object(s) from the RobotState and put them in the world
1542  for (const moveit::core::AttachedBody* attached_body : attached_bodies)
1543  {
1544  const std::string& name = attached_body->getName();
1545  if (world_->hasObject(name))
1546  {
1547  RCLCPP_WARN(LOGGER,
1548  "The collision world already has an object with the same name as the body about to be detached. "
1549  "NOT adding the detached body '%s' to the collision world.",
1550  object.object.id.c_str());
1551  }
1552  else
1553  {
1554  const Eigen::Isometry3d& pose = attached_body->getGlobalPose();
1555  world_->addToObject(name, pose, attached_body->getShapes(), attached_body->getShapePoses());
1556  world_->setSubframesOfObject(name, attached_body->getSubframes());
1557  RCLCPP_DEBUG(LOGGER, "Detached object '%s' from link '%s' and added it back in the collision world",
1558  name.c_str(), object.link_name.c_str());
1559  }
1560 
1561  robot_state_->clearAttachedBody(name);
1562  }
1563  if (!attached_bodies.empty() || object.object.id.empty())
1564  return true;
1565  }
1566  else if (object.object.operation == moveit_msgs::msg::CollisionObject::MOVE)
1567  {
1568  RCLCPP_ERROR(LOGGER, "Move for attached objects not yet implemented");
1569  }
1570  else
1571  {
1572  RCLCPP_ERROR(LOGGER, "Unknown collision object operation: %d", object.object.operation);
1573  }
1574 
1575  return false;
1576 }
1577 
1578 bool PlanningScene::processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject& object)
1579 {
1580  if (object.id == OCTOMAP_NS)
1581  {
1582  RCLCPP_ERROR(LOGGER, "The ID '%s' cannot be used for collision objects (name reserved)", OCTOMAP_NS.c_str());
1583  return false;
1584  }
1585 
1586  if (object.operation == moveit_msgs::msg::CollisionObject::ADD ||
1587  object.operation == moveit_msgs::msg::CollisionObject::APPEND)
1588  {
1589  return processCollisionObjectAdd(object);
1590  }
1591  else if (object.operation == moveit_msgs::msg::CollisionObject::REMOVE)
1592  {
1593  return processCollisionObjectRemove(object);
1594  }
1595  else if (object.operation == moveit_msgs::msg::CollisionObject::MOVE)
1596  {
1597  return processCollisionObjectMove(object);
1598  }
1599 
1600  RCLCPP_ERROR(LOGGER, "Unknown collision object operation: %d", object.operation);
1601  return false;
1602 }
1603 
1604 void PlanningScene::poseMsgToEigen(const geometry_msgs::msg::Pose& msg, Eigen::Isometry3d& out)
1605 {
1606  Eigen::Translation3d translation(msg.position.x, msg.position.y, msg.position.z);
1607  Eigen::Quaterniond quaternion(msg.orientation.w, msg.orientation.x, msg.orientation.y, msg.orientation.z);
1608  if ((quaternion.x() == 0) && (quaternion.y() == 0) && (quaternion.z() == 0) && (quaternion.w() == 0))
1609  {
1610  RCLCPP_WARN(LOGGER, "Empty quaternion found in pose message. Setting to neutral orientation.");
1611  quaternion.setIdentity();
1612  }
1613  else
1614  {
1615  quaternion.normalize();
1616  }
1617  out = translation * quaternion;
1618 }
1619 
1620 bool PlanningScene::shapesAndPosesFromCollisionObjectMessage(const moveit_msgs::msg::CollisionObject& object,
1621  Eigen::Isometry3d& object_pose,
1622  std::vector<shapes::ShapeConstPtr>& shapes,
1623  EigenSTL::vector_Isometry3d& shape_poses)
1624 {
1625  if (object.primitives.size() < object.primitive_poses.size())
1626  {
1627  RCLCPP_ERROR(LOGGER, "More primitive shape poses than shapes in collision object message.");
1628  return false;
1629  }
1630  if (object.meshes.size() < object.mesh_poses.size())
1631  {
1632  RCLCPP_ERROR(LOGGER, "More mesh poses than meshes in collision object message.");
1633  return false;
1634  }
1635  if (object.planes.size() < object.plane_poses.size())
1636  {
1637  RCLCPP_ERROR(LOGGER, "More plane poses than planes in collision object message.");
1638  return false;
1639  }
1640 
1641  const int num_shapes = object.primitives.size() + object.meshes.size() + object.planes.size();
1642  shapes.reserve(num_shapes);
1643  shape_poses.reserve(num_shapes);
1644 
1645  PlanningScene::poseMsgToEigen(object.pose, object_pose);
1646 
1647  bool switch_object_pose_and_shape_pose = false;
1648  if (num_shapes == 1)
1649  if (moveit::core::isEmpty(object.pose))
1650  {
1651  switch_object_pose_and_shape_pose = true; // If the object pose is not set but the shape pose is,
1652  // use the shape's pose as the object pose.
1653  }
1654 
1655  auto append = [&object_pose, &shapes, &shape_poses,
1656  &switch_object_pose_and_shape_pose](shapes::Shape* s, const geometry_msgs::msg::Pose& pose_msg) {
1657  if (!s)
1658  return;
1659  Eigen::Isometry3d pose;
1660  PlanningScene::poseMsgToEigen(pose_msg, pose);
1661  if (!switch_object_pose_and_shape_pose)
1662  shape_poses.emplace_back(std::move(pose));
1663  else
1664  {
1665  shape_poses.emplace_back(std::move(object_pose));
1666  object_pose = pose;
1667  }
1668  shapes.emplace_back(shapes::ShapeConstPtr(s));
1669  };
1670 
1671  auto treat_shape_vectors = [&append](const auto& shape_vector, // the shape_msgs of each type
1672  const auto& shape_poses_vector, // std::vector<const geometry_msgs::Pose>
1673  const std::string& shape_type) {
1674  if (shape_vector.size() > shape_poses_vector.size())
1675  {
1676  RCLCPP_DEBUG_STREAM(LOGGER, "Number of " << shape_type
1677  << " does not match number of poses "
1678  "in collision object message. Assuming identity.");
1679  for (std::size_t i = 0; i < shape_vector.size(); ++i)
1680  {
1681  if (i >= shape_poses_vector.size())
1682  {
1683  append(shapes::constructShapeFromMsg(shape_vector[i]),
1684  geometry_msgs::msg::Pose()); // Empty shape pose => Identity
1685  }
1686  else
1687  append(shapes::constructShapeFromMsg(shape_vector[i]), shape_poses_vector[i]);
1688  }
1689  }
1690  else
1691  for (std::size_t i = 0; i < shape_vector.size(); ++i)
1692  append(shapes::constructShapeFromMsg(shape_vector[i]), shape_poses_vector[i]);
1693  };
1694 
1695  treat_shape_vectors(object.primitives, object.primitive_poses, std::string("primitive_poses"));
1696  treat_shape_vectors(object.meshes, object.mesh_poses, std::string("meshes"));
1697  treat_shape_vectors(object.planes, object.plane_poses, std::string("planes"));
1698  return true;
1699 }
1700 
1701 bool PlanningScene::processCollisionObjectAdd(const moveit_msgs::msg::CollisionObject& object)
1702 {
1703  if (!knowsFrameTransform(object.header.frame_id))
1704  {
1705  RCLCPP_ERROR_STREAM(LOGGER, "Unknown frame: " << object.header.frame_id);
1706  return false;
1707  }
1708 
1709  if (object.primitives.empty() && object.meshes.empty() && object.planes.empty())
1710  {
1711  RCLCPP_ERROR(LOGGER, "There are no shapes specified in the collision object message");
1712  return false;
1713  }
1714 
1715  // replace the object if ADD is specified instead of APPEND
1716  if (object.operation == moveit_msgs::msg::CollisionObject::ADD && world_->hasObject(object.id))
1717  world_->removeObject(object.id);
1718 
1719  const Eigen::Isometry3d& world_to_object_header_transform = getFrameTransform(object.header.frame_id);
1720  Eigen::Isometry3d header_to_pose_transform;
1721  std::vector<shapes::ShapeConstPtr> shapes;
1722  EigenSTL::vector_Isometry3d shape_poses;
1723  if (!shapesAndPosesFromCollisionObjectMessage(object, header_to_pose_transform, shapes, shape_poses))
1724  return false;
1725  const Eigen::Isometry3d object_frame_transform = world_to_object_header_transform * header_to_pose_transform;
1726 
1727  world_->addToObject(object.id, object_frame_transform, shapes, shape_poses);
1728 
1729  if (!object.type.key.empty() || !object.type.db.empty())
1730  setObjectType(object.id, object.type);
1731 
1732  // Add subframes
1734  Eigen::Isometry3d subframe_pose;
1735  for (std::size_t i = 0; i < object.subframe_poses.size(); ++i)
1736  {
1737  PlanningScene::poseMsgToEigen(object.subframe_poses[i], subframe_pose);
1738  std::string name = object.subframe_names[i];
1739  subframes[name] = subframe_pose;
1740  }
1741  world_->setSubframesOfObject(object.id, subframes);
1742  return true;
1743 }
1744 
1745 bool PlanningScene::processCollisionObjectRemove(const moveit_msgs::msg::CollisionObject& object)
1746 {
1747  if (object.id.empty())
1748  {
1750  }
1751  else
1752  {
1753  if (!world_->removeObject(object.id))
1754  {
1755  RCLCPP_WARN_STREAM(LOGGER,
1756  "Tried to remove world object '" << object.id << "', but it does not exist in this scene.");
1757  return false;
1758  }
1759 
1760  removeObjectColor(object.id);
1761  removeObjectType(object.id);
1762  }
1763  return true;
1764 }
1765 
1766 bool PlanningScene::processCollisionObjectMove(const moveit_msgs::msg::CollisionObject& object)
1767 {
1768  if (world_->hasObject(object.id))
1769  {
1770  if (!object.primitives.empty() || !object.meshes.empty() || !object.planes.empty())
1771  RCLCPP_WARN(LOGGER, "Move operation for object '%s' ignores the geometry specified in the message.",
1772  object.id.c_str());
1773 
1774  const Eigen::Isometry3d& world_to_object_header_transform = getFrameTransform(object.header.frame_id);
1775  Eigen::Isometry3d header_to_pose_transform;
1776 
1777  PlanningScene::poseMsgToEigen(object.pose, header_to_pose_transform);
1778 
1779  const Eigen::Isometry3d object_frame_transform = world_to_object_header_transform * header_to_pose_transform;
1780  world_->setObjectPose(object.id, object_frame_transform);
1781  return true;
1782  }
1783 
1784  RCLCPP_ERROR(LOGGER, "World object '%s' does not exist. Cannot move.", object.id.c_str());
1785  return false;
1786 }
1787 
1788 const Eigen::Isometry3d& PlanningScene::getFrameTransform(const std::string& frame_id) const
1789 {
1791 }
1792 
1793 const Eigen::Isometry3d& PlanningScene::getFrameTransform(const std::string& frame_id)
1794 {
1795  if (getCurrentState().dirtyLinkTransforms())
1797  else
1799 }
1800 
1801 const Eigen::Isometry3d& PlanningScene::getFrameTransform(const moveit::core::RobotState& state,
1802  const std::string& frame_id) const
1803 {
1804  if (!frame_id.empty() && frame_id[0] == '/')
1805  // Recursively call itself without the slash in front of frame name
1806  return getFrameTransform(frame_id.substr(1));
1807 
1808  bool frame_found;
1809  const Eigen::Isometry3d& t1 = state.getFrameTransform(frame_id, &frame_found);
1810  if (frame_found)
1811  return t1;
1812 
1813  const Eigen::Isometry3d& t2 = getWorld()->getTransform(frame_id, frame_found);
1814  if (frame_found)
1815  return t2;
1816  return getTransforms().Transforms::getTransform(frame_id);
1817 }
1818 
1819 bool PlanningScene::knowsFrameTransform(const std::string& frame_id) const
1820 {
1822 }
1823 
1824 bool PlanningScene::knowsFrameTransform(const moveit::core::RobotState& state, const std::string& frame_id) const
1825 {
1826  if (!frame_id.empty() && frame_id[0] == '/')
1827  return knowsFrameTransform(frame_id.substr(1));
1828 
1829  if (state.knowsFrameTransform(frame_id))
1830  return true;
1831  if (getWorld()->knowsTransform(frame_id))
1832  return true;
1833  return getTransforms().Transforms::canTransform(frame_id);
1834 }
1835 
1836 bool PlanningScene::hasObjectType(const std::string& object_id) const
1837 {
1838  if (object_types_)
1839  if (object_types_->find(object_id) != object_types_->end())
1840  return true;
1841  if (parent_)
1842  return parent_->hasObjectType(object_id);
1843  return false;
1844 }
1845 
1846 const object_recognition_msgs::msg::ObjectType& PlanningScene::getObjectType(const std::string& object_id) const
1847 {
1848  if (object_types_)
1849  {
1850  ObjectTypeMap::const_iterator it = object_types_->find(object_id);
1851  if (it != object_types_->end())
1852  return it->second;
1853  }
1854  if (parent_)
1855  return parent_->getObjectType(object_id);
1856  static const object_recognition_msgs::msg::ObjectType EMPTY;
1857  return EMPTY;
1858 }
1859 
1860 void PlanningScene::setObjectType(const std::string& object_id, const object_recognition_msgs::msg::ObjectType& type)
1861 {
1862  if (!object_types_)
1863  object_types_ = std::make_unique<ObjectTypeMap>();
1864  (*object_types_)[object_id] = type;
1865 }
1866 
1867 void PlanningScene::removeObjectType(const std::string& object_id)
1868 {
1869  if (object_types_)
1870  object_types_->erase(object_id);
1871 }
1872 
1874 {
1875  kc.clear();
1876  if (parent_)
1877  parent_->getKnownObjectTypes(kc);
1878  if (object_types_)
1879  for (ObjectTypeMap::const_iterator it = object_types_->begin(); it != object_types_->end(); ++it)
1880  kc[it->first] = it->second;
1881 }
1882 
1883 bool PlanningScene::hasObjectColor(const std::string& object_id) const
1884 {
1885  if (object_colors_)
1886  if (object_colors_->find(object_id) != object_colors_->end())
1887  return true;
1888  if (parent_)
1889  return parent_->hasObjectColor(object_id);
1890  return false;
1891 }
1892 
1893 const std_msgs::msg::ColorRGBA& PlanningScene::getObjectColor(const std::string& object_id) const
1894 {
1895  if (object_colors_)
1896  {
1897  ObjectColorMap::const_iterator it = object_colors_->find(object_id);
1898  if (it != object_colors_->end())
1899  return it->second;
1900  }
1901  if (parent_)
1902  return parent_->getObjectColor(object_id);
1903  static const std_msgs::msg::ColorRGBA EMPTY;
1904  return EMPTY;
1905 }
1906 
1908 {
1909  kc.clear();
1910  if (parent_)
1911  parent_->getKnownObjectColors(kc);
1912  if (object_colors_)
1913  for (ObjectColorMap::const_iterator it = object_colors_->begin(); it != object_colors_->end(); ++it)
1914  kc[it->first] = it->second;
1915 }
1916 
1917 void PlanningScene::setObjectColor(const std::string& object_id, const std_msgs::msg::ColorRGBA& color)
1918 {
1919  if (object_id.empty())
1920  {
1921  RCLCPP_ERROR(LOGGER, "Cannot set color of object with empty object_id.");
1922  return;
1923  }
1924  if (!object_colors_)
1925  object_colors_ = std::make_unique<ObjectColorMap>();
1926  (*object_colors_)[object_id] = color;
1927 }
1928 
1929 void PlanningScene::removeObjectColor(const std::string& object_id)
1930 {
1931  if (object_colors_)
1932  object_colors_->erase(object_id);
1933 }
1934 
1935 bool PlanningScene::isStateColliding(const moveit_msgs::msg::RobotState& state, const std::string& group,
1936  bool verbose) const
1937 {
1940  return isStateColliding(s, group, verbose);
1941 }
1942 
1943 bool PlanningScene::isStateColliding(const std::string& group, bool verbose)
1944 {
1945  if (getCurrentState().dirtyCollisionBodyTransforms())
1946  return isStateColliding(getCurrentStateNonConst(), group, verbose);
1947  else
1948  return isStateColliding(getCurrentState(), group, verbose);
1949 }
1950 
1951 bool PlanningScene::isStateColliding(const moveit::core::RobotState& state, const std::string& group, bool verbose) const
1952 {
1954  req.verbose = verbose;
1955  req.group_name = group;
1957  checkCollision(req, res, state);
1958  return res.collision;
1959 }
1960 
1961 bool PlanningScene::isStateFeasible(const moveit_msgs::msg::RobotState& state, bool verbose) const
1962 {
1963  if (state_feasibility_)
1964  {
1967  return state_feasibility_(s, verbose);
1968  }
1969  return true;
1970 }
1971 
1972 bool PlanningScene::isStateFeasible(const moveit::core::RobotState& state, bool verbose) const
1973 {
1974  if (state_feasibility_)
1975  return state_feasibility_(state, verbose);
1976  return true;
1977 }
1978 
1979 bool PlanningScene::isStateConstrained(const moveit_msgs::msg::RobotState& state,
1980  const moveit_msgs::msg::Constraints& constr, bool verbose) const
1981 {
1984  return isStateConstrained(s, constr, verbose);
1985 }
1986 
1988  const moveit_msgs::msg::Constraints& constr, bool verbose) const
1989 {
1990  kinematic_constraints::KinematicConstraintSetPtr ks(
1992  ks->add(constr, getTransforms());
1993  if (ks->empty())
1994  return true;
1995  else
1996  return isStateConstrained(state, *ks, verbose);
1997 }
1998 
1999 bool PlanningScene::isStateConstrained(const moveit_msgs::msg::RobotState& state,
2000  const kinematic_constraints::KinematicConstraintSet& constr, bool verbose) const
2001 {
2004  return isStateConstrained(s, constr, verbose);
2005 }
2006 
2008  const kinematic_constraints::KinematicConstraintSet& constr, bool verbose) const
2009 {
2010  return constr.decide(state, verbose).satisfied;
2011 }
2012 
2013 bool PlanningScene::isStateValid(const moveit::core::RobotState& state, const std::string& group, bool verbose) const
2014 {
2015  static const moveit_msgs::msg::Constraints EMP_CONSTRAINTS;
2016  return isStateValid(state, EMP_CONSTRAINTS, group, verbose);
2017 }
2018 
2019 bool PlanningScene::isStateValid(const moveit_msgs::msg::RobotState& state, const std::string& group, bool verbose) const
2020 {
2021  static const moveit_msgs::msg::Constraints EMP_CONSTRAINTS;
2022  return isStateValid(state, EMP_CONSTRAINTS, group, verbose);
2023 }
2024 
2025 bool PlanningScene::isStateValid(const moveit_msgs::msg::RobotState& state, const moveit_msgs::msg::Constraints& constr,
2026  const std::string& group, bool verbose) const
2027 {
2030  return isStateValid(s, constr, group, verbose);
2031 }
2032 
2033 bool PlanningScene::isStateValid(const moveit::core::RobotState& state, const moveit_msgs::msg::Constraints& constr,
2034  const std::string& group, bool verbose) const
2035 {
2036  if (isStateColliding(state, group, verbose))
2037  return false;
2038  if (!isStateFeasible(state, verbose))
2039  return false;
2040  return isStateConstrained(state, constr, verbose);
2041 }
2042 
2044  const kinematic_constraints::KinematicConstraintSet& constr, const std::string& group,
2045  bool verbose) const
2046 {
2047  if (isStateColliding(state, group, verbose))
2048  return false;
2049  if (!isStateFeasible(state, verbose))
2050  return false;
2051  return isStateConstrained(state, constr, verbose);
2052 }
2053 
2054 bool PlanningScene::isPathValid(const moveit_msgs::msg::RobotState& start_state,
2055  const moveit_msgs::msg::RobotTrajectory& trajectory, const std::string& group,
2056  bool verbose, std::vector<std::size_t>* invalid_index) const
2057 {
2058  static const moveit_msgs::msg::Constraints EMP_CONSTRAINTS;
2059  static const std::vector<moveit_msgs::msg::Constraints> EMP_CONSTRAINTS_VECTOR;
2060  return isPathValid(start_state, trajectory, EMP_CONSTRAINTS, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2061 }
2062 
2063 bool PlanningScene::isPathValid(const moveit_msgs::msg::RobotState& start_state,
2064  const moveit_msgs::msg::RobotTrajectory& trajectory,
2065  const moveit_msgs::msg::Constraints& path_constraints, const std::string& group,
2066  bool verbose, std::vector<std::size_t>* invalid_index) const
2067 {
2068  static const std::vector<moveit_msgs::msg::Constraints> EMP_CONSTRAINTS_VECTOR;
2069  return isPathValid(start_state, trajectory, path_constraints, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2070 }
2071 
2072 bool PlanningScene::isPathValid(const moveit_msgs::msg::RobotState& start_state,
2073  const moveit_msgs::msg::RobotTrajectory& trajectory,
2074  const moveit_msgs::msg::Constraints& path_constraints,
2075  const moveit_msgs::msg::Constraints& goal_constraints, const std::string& group,
2076  bool verbose, std::vector<std::size_t>* invalid_index) const
2077 {
2078  std::vector<moveit_msgs::msg::Constraints> goal_constraints_vector(1, goal_constraints);
2079  return isPathValid(start_state, trajectory, path_constraints, goal_constraints_vector, group, verbose, invalid_index);
2080 }
2081 
2082 bool PlanningScene::isPathValid(const moveit_msgs::msg::RobotState& start_state,
2083  const moveit_msgs::msg::RobotTrajectory& trajectory,
2084  const moveit_msgs::msg::Constraints& path_constraints,
2085  const std::vector<moveit_msgs::msg::Constraints>& goal_constraints,
2086  const std::string& group, bool verbose, std::vector<std::size_t>* invalid_index) const
2087 {
2091  t.setRobotTrajectoryMsg(start, trajectory);
2092  return isPathValid(t, path_constraints, goal_constraints, group, verbose, invalid_index);
2093 }
2094 
2096  const moveit_msgs::msg::Constraints& path_constraints,
2097  const std::vector<moveit_msgs::msg::Constraints>& goal_constraints,
2098  const std::string& group, bool verbose, std::vector<std::size_t>* invalid_index) const
2099 {
2100  bool result = true;
2101  if (invalid_index)
2102  invalid_index->clear();
2105  std::size_t n_wp = trajectory.getWayPointCount();
2106  for (std::size_t i = 0; i < n_wp; ++i)
2107  {
2108  const moveit::core::RobotState& st = trajectory.getWayPoint(i);
2109 
2110  bool this_state_valid = true;
2111  if (isStateColliding(st, group, verbose))
2112  this_state_valid = false;
2113  if (!isStateFeasible(st, verbose))
2114  this_state_valid = false;
2115  if (!ks_p.empty() && !ks_p.decide(st, verbose).satisfied)
2116  this_state_valid = false;
2117 
2118  if (!this_state_valid)
2119  {
2120  if (invalid_index)
2121  invalid_index->push_back(i);
2122  else
2123  return false;
2124  result = false;
2125  }
2126 
2127  // check goal for last state
2128  if (i + 1 == n_wp && !goal_constraints.empty())
2129  {
2130  bool found = false;
2131  for (const moveit_msgs::msg::Constraints& goal_constraint : goal_constraints)
2132  {
2133  if (isStateConstrained(st, goal_constraint))
2134  {
2135  found = true;
2136  break;
2137  }
2138  }
2139  if (!found)
2140  {
2141  if (verbose)
2142  RCLCPP_INFO(LOGGER, "Goal not satisfied");
2143  if (invalid_index)
2144  invalid_index->push_back(i);
2145  result = false;
2146  }
2147  }
2148  }
2149  return result;
2150 }
2151 
2153  const moveit_msgs::msg::Constraints& path_constraints,
2154  const moveit_msgs::msg::Constraints& goal_constraints, const std::string& group,
2155  bool verbose, std::vector<std::size_t>* invalid_index) const
2156 {
2157  std::vector<moveit_msgs::msg::Constraints> goal_constraints_vector(1, goal_constraints);
2158  return isPathValid(trajectory, path_constraints, goal_constraints_vector, group, verbose, invalid_index);
2159 }
2160 
2162  const moveit_msgs::msg::Constraints& path_constraints, const std::string& group,
2163  bool verbose, std::vector<std::size_t>* invalid_index) const
2164 {
2165  static const std::vector<moveit_msgs::msg::Constraints> EMP_CONSTRAINTS_VECTOR;
2166  return isPathValid(trajectory, path_constraints, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2167 }
2168 
2169 bool PlanningScene::isPathValid(const robot_trajectory::RobotTrajectory& trajectory, const std::string& group,
2170  bool verbose, std::vector<std::size_t>* invalid_index) const
2171 {
2172  static const moveit_msgs::msg::Constraints EMP_CONSTRAINTS;
2173  static const std::vector<moveit_msgs::msg::Constraints> EMP_CONSTRAINTS_VECTOR;
2174  return isPathValid(trajectory, EMP_CONSTRAINTS, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2175 }
2176 
2177 void PlanningScene::getCostSources(const robot_trajectory::RobotTrajectory& trajectory, std::size_t max_costs,
2178  std::set<collision_detection::CostSource>& costs, double overlap_fraction) const
2179 {
2180  getCostSources(trajectory, max_costs, std::string(), costs, overlap_fraction);
2181 }
2182 
2183 void PlanningScene::getCostSources(const robot_trajectory::RobotTrajectory& trajectory, std::size_t max_costs,
2184  const std::string& group_name, std::set<collision_detection::CostSource>& costs,
2185  double overlap_fraction) const
2186 {
2188  creq.max_cost_sources = max_costs;
2189  creq.group_name = group_name;
2190  creq.cost = true;
2191  std::set<collision_detection::CostSource> cs;
2192  std::set<collision_detection::CostSource> cs_start;
2193  std::size_t n_wp = trajectory.getWayPointCount();
2194  for (std::size_t i = 0; i < n_wp; ++i)
2195  {
2197  checkCollision(creq, cres, trajectory.getWayPoint(i));
2198  cs.insert(cres.cost_sources.begin(), cres.cost_sources.end());
2199  if (i == 0)
2200  cs_start.swap(cres.cost_sources);
2201  }
2202 
2203  if (cs.size() <= max_costs)
2204  costs.swap(cs);
2205  else
2206  {
2207  costs.clear();
2208  std::size_t i = 0;
2209  for (std::set<collision_detection::CostSource>::iterator it = cs.begin(); i < max_costs; ++it, ++i)
2210  costs.insert(*it);
2211  }
2212 
2213  collision_detection::removeCostSources(costs, cs_start, overlap_fraction);
2214  collision_detection::removeOverlapping(costs, overlap_fraction);
2215 }
2216 
2217 void PlanningScene::getCostSources(const moveit::core::RobotState& state, std::size_t max_costs,
2218  std::set<collision_detection::CostSource>& costs) const
2219 {
2220  getCostSources(state, max_costs, std::string(), costs);
2221 }
2222 
2223 void PlanningScene::getCostSources(const moveit::core::RobotState& state, std::size_t max_costs,
2224  const std::string& group_name,
2225  std::set<collision_detection::CostSource>& costs) const
2226 {
2228  creq.max_cost_sources = max_costs;
2229  creq.group_name = group_name;
2230  creq.cost = true;
2232  checkCollision(creq, cres, state);
2233  cres.cost_sources.swap(costs);
2234 }
2235 
2236 void PlanningScene::printKnownObjects(std::ostream& out) const
2237 {
2238  const std::vector<std::string>& objects = getWorld()->getObjectIds();
2239  std::vector<const moveit::core::AttachedBody*> attached_bodies;
2240  getCurrentState().getAttachedBodies(attached_bodies);
2241 
2242  // Output
2243  out << "-----------------------------------------\n";
2244  out << "PlanningScene Known Objects:\n";
2245  out << " - Collision World Objects:\n ";
2246  for (const std::string& object : objects)
2247  {
2248  out << "\t- " << object << "\n";
2249  }
2250 
2251  out << " - Attached Bodies:\n";
2252  for (const moveit::core::AttachedBody* attached_body : attached_bodies)
2253  {
2254  out << "\t- " << attached_body->getName() << "\n";
2255  }
2256  out << "-----------------------------------------\n";
2257 }
2258 
2259 } // end of namespace planning_scene
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
void getMessage(moveit_msgs::msg::AllowedCollisionMatrix &msg) const
Get the allowed collision matrix as a message.
World::ObjectConstPtr ObjectConstPtr
std::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
Definition: world.h:301
A class that contains many different constraints, and can check RobotState *versus the full set....
bool empty() const
Returns whether or not there are any constraints in the set.
bool add(const moveit_msgs::msg::Constraints &c, const moveit::core::Transforms &tf)
Add all known constraints.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const
Determines whether all constraints are satisfied by state, returning a single evaluation result.
This may be thrown during construction of objects if errors occur.
Definition: exceptions.h:46
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:58
const std::string & getAttachedLinkName() const
Get the name of the link this body is attached to.
Definition: attached_body.h:92
const std::set< std::string > & getTouchLinks() const
Get the links that the attached body is allowed to touch.
const trajectory_msgs::msg::JointTrajectory & getDetachPosture() const
Return the posture that is necessary for the object to be released, (if any). This is useful for exam...
const moveit::core::FixedTransformsMap & getSubframes() const
Get subframes of this object (relative to the object pose). The returned transforms are guaranteed to...
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get the shapes that make up this attached body.
const Eigen::Isometry3d & getPose() const
Get the pose of the attached body relative to the parent link.
Definition: attached_body.h:80
const EigenSTL::vector_Isometry3d & getShapePoses() const
Get the shape poses (the transforms to the shapes of this body, relative to the pose)....
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void update(bool force=false)
Update all transforms.
bool knowsFrameTransform(const std::string &frame_id) const
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known.
Provides an implementation of a snapshot of a transform tree that can be easily queried for transform...
Definition: transforms.h:59
Transforms(const Transforms &)=delete
Transforms cannot be copy-constructed.
void copyTransforms(std::vector< geometry_msgs::msg::TransformStamped > &transforms) const
Get a vector of all the transforms as ROS messages.
Definition: transforms.cpp:164
This class maintains the representation of the environment as seen by a planning instance....
void getAttachedCollisionObjectMsgs(std::vector< moveit_msgs::msg::AttachedCollisionObject > &attached_collision_objs) const
Construct a vector of messages (attached_collision_objects) with the attached collision object data f...
bool usePlanningSceneMsg(const moveit_msgs::msg::PlanningScene &scene)
Call setPlanningSceneMsg() or setPlanningSceneDiffMsg() depending on how the is_diff member of the me...
void getPlanningSceneMsg(moveit_msgs::msg::PlanningScene &scene) const
Construct a message (scene) with all the necessary data so that the scene can be later reconstructed ...
collision_detection::AllowedCollisionMatrix & getAllowedCollisionMatrixNonConst()
Get the allowed collision matrix.
bool isStateFeasible(const moveit_msgs::msg::RobotState &state, bool verbose=false) const
Check if a given state is feasible, in accordance to the feasibility predicate specified by setStateF...
static PlanningScenePtr clone(const PlanningSceneConstPtr &scene)
Clone a planning scene. Even if the scene scene depends on a parent, the cloned scene will not.
bool processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject &object)
void setCurrentState(const moveit_msgs::msg::RobotState &state)
Set the current robot state to be state. If not all joint values are specified, the previously mainta...
moveit::core::RobotStatePtr getCurrentStateUpdated(const moveit_msgs::msg::RobotState &update) const
Get a copy of the current state with components overwritten by the state message update.
const std::string & getName() const
Get the name of the planning scene. This is empty by default.
const Eigen::Isometry3d & getFrameTransform(const std::string &id) const
Get the transform corresponding to the frame id. This will be known if id is a link name,...
const object_recognition_msgs::msg::ObjectType & getObjectType(const std::string &id) const
void getObjectColorMsgs(std::vector< moveit_msgs::msg::ObjectColor > &object_colors) const
Construct a vector of messages (object_colors) with the colors of the objects from the planning_scene...
const collision_detection::CollisionEnvPtr & getCollisionEnvNonConst()
Get the representation of the collision robot This can be used to set padding and link scale on the a...
bool getCollisionObjectMsg(moveit_msgs::msg::CollisionObject &collision_obj, const std::string &ns) const
Construct a message (collision_object) with the collision object data from the planning_scene for the...
const std::string & getPlanningFrame() const
Get the frame in which planning is performed.
bool isPathValid(const moveit_msgs::msg::RobotState &start_state, const moveit_msgs::msg::RobotTrajectory &trajectory, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const
Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibili...
void checkCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
Check whether the current state is in collision, and if needed, updates the collision transforms of t...
bool knowsFrameTransform(const std::string &id) const
Check if a transform to the frame id is known. This will be known if id is a link name,...
void getCollisionObjectMsgs(std::vector< moveit_msgs::msg::CollisionObject > &collision_objs) const
Construct a vector of messages (collision_objects) with the collision object data for all objects in ...
moveit::core::RobotState & getCurrentStateNonConst()
Get the state at which the robot is assumed to be.
bool isStateValid(const moveit_msgs::msg::RobotState &state, const std::string &group="", bool verbose=false) const
Check if a given state is valid. This means checking for collisions and feasibility.
void checkCollisionUnpadded(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
Check whether the current state is in collision, but use a collision_detection::CollisionRobot instan...
void processOctomapMsg(const octomap_msgs::msg::OctomapWithPose &map)
void getPlanningSceneDiffMsg(moveit_msgs::msg::PlanningScene &scene) const
Fill the message scene with the differences between this instance of PlanningScene with respect to th...
void getKnownObjectColors(ObjectColorMap &kc) const
bool loadGeometryFromStream(std::istream &in)
Load the geometry of the planning scene from a stream.
PlanningScenePtr diff() const
Return a new child PlanningScene that uses this one as parent.
const collision_detection::CollisionEnvConstPtr & getCollisionEnvUnpadded() const
Get the active collision detector for the robot.
bool setPlanningSceneDiffMsg(const moveit_msgs::msg::PlanningScene &scene)
Apply changes to this planning scene as diffs, even if the message itself is not marked as being a di...
bool processAttachedCollisionObjectMsg(const moveit_msgs::msg::AttachedCollisionObject &object)
bool processPlanningSceneWorldMsg(const moveit_msgs::msg::PlanningSceneWorld &world)
void setObjectColor(const std::string &id, const std_msgs::msg::ColorRGBA &color)
const collision_detection::AllowedCollisionMatrix & getAllowedCollisionMatrix() const
Get the allowed collision matrix.
void getKnownObjectTypes(ObjectTypeMap &kc) const
PlanningScene(const PlanningScene &)=delete
PlanningScene cannot be copy-constructed.
bool hasObjectColor(const std::string &id) const
bool getOctomapMsg(octomap_msgs::msg::OctomapWithPose &octomap) const
Construct a message (octomap) with the octomap data from the planning_scene.
void clearDiffs()
Clear the diffs accumulated for this planning scene, with respect to: the parent PlanningScene (if it...
void setAttachedBodyUpdateCallback(const moveit::core::AttachedBodyCallback &callback)
Set the callback to be triggered when changes are made to the current scene state.
void setObjectType(const std::string &id, const object_recognition_msgs::msg::ObjectType &type)
void printKnownObjects(std::ostream &out=std::cout) const
Outputs debug information about the planning scene contents.
const std::string getCollisionDetectorName() const
void pushDiffs(const PlanningScenePtr &scene)
If there is a parent specified for this scene, then the diffs with respect to that parent are applied...
bool shapesAndPosesFromCollisionObjectMessage(const moveit_msgs::msg::CollisionObject &object, Eigen::Isometry3d &object_pose_in_header_frame, std::vector< shapes::ShapeConstPtr > &shapes, EigenSTL::vector_Isometry3d &shape_poses)
Takes the object message and returns the object pose, shapes and shape poses. If the object pose is e...
bool hasObjectType(const std::string &id) const
void decoupleParent()
Make sure that all the data maintained in this scene is local. All unmodified data is copied from the...
void allocateCollisionDetector(const collision_detection::CollisionDetectorAllocatorPtr &allocator)
Allocate a new collision detector and replace the previous one if there was any.
void getCostSources(const robot_trajectory::RobotTrajectory &trajectory, std::size_t max_costs, std::set< collision_detection::CostSource > &costs, double overlap_fraction=0.9) const
Get the top max_costs cost sources for a specified trajectory. The resulting costs are stored in cost...
const moveit::core::RobotState & getCurrentState() const
Get the state at which the robot is assumed to be.
void removeAllCollisionObjects()
Clear all collision objects in planning scene.
static bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or it is just a default,...
const collision_detection::WorldConstPtr & getWorld() const
Get the representation of the world.
bool isStateColliding(const std::string &group="", bool verbose=false)
Check if the current state is in collision (with the environment or self collision)....
const moveit::core::Transforms & getTransforms() const
Get the set of fixed transforms from known frames to the planning frame.
bool isStateConstrained(const moveit_msgs::msg::RobotState &state, const moveit_msgs::msg::Constraints &constr, bool verbose=false) const
Check if a given state satisfies a set of constraints.
bool setPlanningSceneMsg(const moveit_msgs::msg::PlanningScene &scene)
Set this instance of a planning scene to be the same as the one serialized in the scene message,...
bool getAttachedCollisionObjectMsg(moveit_msgs::msg::AttachedCollisionObject &attached_collision_obj, const std::string &ns) const
Construct a message (attached_collision_object) with the attached collision object data from the plan...
void saveGeometryToStream(std::ostream &out) const
Save the geometry of the planning scene to a stream, as plain text.
void getCollidingLinks(std::vector< std::string > &links)
Get the names of the links that are involved in collisions for the current state.
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the kinematic model for which the planning scene is maintained.
moveit::core::Transforms & getTransformsNonConst()
Get the set of fixed transforms from known frames to the planning frame.
void checkSelfCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
Check whether the current state is in self collision.
const collision_detection::CollisionEnvConstPtr & getCollisionEnv() const
Get the active collision environment.
void removeObjectColor(const std::string &id)
static const std::string OCTOMAP_NS
static const std::string DEFAULT_SCENE_NAME
void setCollisionObjectUpdateCallback(const collision_detection::World::ObserverCallbackFn &callback)
Set the callback to be triggered when changes are made to the current scene world.
void getCollidingPairs(collision_detection::CollisionResult::ContactMap &contacts)
Get the names of the links that are involved in collisions for the current state. Update the link tra...
const std_msgs::msg::ColorRGBA & getObjectColor(const std::string &id) const
friend struct CollisionDetector
Enumerates the available collision detectors.
void processOctomapPtr(const std::shared_ptr< const octomap::OcTree > &octree, const Eigen::Isometry3d &t)
void removeObjectType(const std::string &id)
bool isFixedFrame(const std::string &frame) const override
Check whether a frame stays constant as the state of the robot model changes. This is true for any tr...
const Eigen::Isometry3d & getTransform(const std::string &from_frame) const override
Get transform for from_frame (w.r.t target frame)
SceneTransforms(const PlanningScene *scene)
bool canTransform(const std::string &from_frame) const override
Check whether data can be transformed from a particular frame.
Maintain a sequence of waypoints and the time durations between these waypoints.
RobotTrajectory & setRobotTrajectoryMsg(const moveit::core::RobotState &reference_state, const trajectory_msgs::msg::JointTrajectory &trajectory)
Copy the content of the trajectory message into this class. The trajectory message itself is not requ...
const moveit::core::RobotState & getWayPoint(std::size_t index) const
@ ROBOT_LINK
A link on the robot.
std::shared_ptr< OccMapTree > OccMapTreePtr
void removeCostSources(std::set< CostSource > &cost_sources, const std::set< CostSource > &cost_sources_to_remove, double overlap_fraction)
void removeOverlapping(std::set< CostSource > &cost_sources, double overlap_fraction)
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
void attachedBodiesToAttachedCollisionObjectMsgs(const std::vector< const AttachedBody * > &attached_bodies, std::vector< moveit_msgs::msg::AttachedCollisionObject > &attached_collision_objs)
Convert AttachedBodies to AttachedCollisionObjects.
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
Definition: transforms.h:53
std::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
Definition: attached_body.h:51
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
frame_id
Definition: pick.py:63
scene
Definition: pick.py:52
p
Definition: pick.py:62
x
Definition: pick.py:64
y
Definition: pick.py:65
z
Definition: pick.py:66
a
Definition: plan.py:54
r
Definition: plan.py:56
This namespace includes the central class for representing planning contexts.
std::map< std::string, std_msgs::msg::ColorRGBA > ObjectColorMap
A map from object names (e.g., attached bodies, collision objects) to their colors.
std::map< std::string, object_recognition_msgs::msg::ObjectType > ObjectTypeMap
A map from object names (e.g., attached bodies, collision objects) to their types.
collision_detection::OccMapTreePtr createOctomap(const octomap_msgs::msg::Octomap &map)
std::string append(const std::string &left, const std::string &right)
name
Definition: setup.py:7
Definition: world.h:49
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
bool verbose
Flag indicating whether information about detected collisions should be reported.
std::size_t max_cost_sources
When costs are computed, this value defines how many of the top cost sources should be returned.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
bool cost
If true, a collision cost is computed.
std::size_t max_contacts
Overall maximum number of contacts to compute.
std::size_t max_contacts_per_pair
Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at differ...
Representation of a collision checking result.
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
A map returning the pairs of body ids in contact, plus their contact details.
std::set< CostSource > cost_sources
These are the individual cost sources when costs are computed.
bool collision
True if collision was found, false otherwise.
Definition of a contact point.
std::string body_name_2
The id of the second body involved in the contact.
std::string body_name_1
The id of the first body involved in the contact.
BodyType body_type_1
The type of the first body involved in the contact.
BodyType body_type_2
The type of the second body involved in the contact.
A representation of an object.
Definition: world.h:79
moveit::core::FixedTransformsMap subframe_poses_
Transforms from the object pose to subframes on the object. Use them to define points of interest on ...
Definition: world.h:112
Eigen::Isometry3d pose_
The object's pose. All shapes and subframes are defined relative to this frame. This frame is returne...
Definition: world.h:91
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string id_
The id for this object.
Definition: world.h:87
EigenSTL::vector_Isometry3d shape_poses_
The poses of the corresponding entries in shapes_, relative to the object pose.
Definition: world.h:101
std::vector< shapes::ShapeConstPtr > shapes_
All the shapes making up this object.
Definition: world.h:96
bool satisfied
Whether or not the constraint or constraints were satisfied.