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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Feb 9 2025 03:25:06