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  scene->getAllowedCollisionMatrixNonConst().removeEntry(it.first);
446  }
447  else
448  {
449  const collision_detection::World::Object& obj = *world_->getObject(it.first);
450  scene->world_->removeObject(obj.id_);
451  scene->world_->addToObject(obj.id_, obj.pose_, obj.shapes_, obj.shape_poses_);
452  if (hasObjectColor(it.first))
453  scene->setObjectColor(it.first, getObjectColor(it.first));
454  if (hasObjectType(it.first))
455  scene->setObjectType(it.first, getObjectType(it.first));
456 
457  scene->world_->setSubframesOfObject(obj.id_, obj.subframe_poses_);
458  }
459  }
460  }
461 }
462 
465 {
466  if (getCurrentState().dirtyCollisionBodyTransforms())
468  else
469  checkCollision(req, res, getCurrentState());
470 }
471 
475 {
477 }
478 
481 {
482  if (getCurrentState().dirtyCollisionBodyTransforms())
484  else
485  checkSelfCollision(req, res, getCurrentState());
486 }
487 
492 {
493  // check collision with the world using the padded version
494  getCollisionEnv()->checkRobotCollision(req, res, robot_state, acm);
495 
496  // do self-collision checking with the unpadded version of the robot
497  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
498  getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm);
499 }
500 
503 {
504  if (getCurrentState().dirtyCollisionBodyTransforms())
506  else
508 }
509 
514 {
515  // check collision with the world using the unpadded version
516  getCollisionEnvUnpadded()->checkRobotCollision(req, res, robot_state, acm);
517 
518  // do self-collision checking with the unpadded version of the robot
519  if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts))
520  {
521  getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm);
522  }
523 }
524 
526 {
527  if (getCurrentState().dirtyCollisionBodyTransforms())
529  else
531 }
532 
536  const std::string& group_name) const
537 {
539  req.contacts = true;
540  req.max_contacts = getRobotModel()->getLinkModelsWithCollisionGeometry().size() + 1;
541  req.max_contacts_per_pair = 1;
542  req.group_name = group_name;
544  checkCollision(req, res, robot_state, acm);
545  res.contacts.swap(contacts);
546 }
547 
548 void PlanningScene::getCollidingLinks(std::vector<std::string>& links)
549 {
550  if (getCurrentState().dirtyCollisionBodyTransforms())
552  else
554 }
555 
556 void PlanningScene::getCollidingLinks(std::vector<std::string>& links, const moveit::core::RobotState& robot_state,
558 {
560  getCollidingPairs(contacts, robot_state, acm);
561  links.clear();
562  for (collision_detection::CollisionResult::ContactMap::const_iterator it = contacts.begin(); it != contacts.end();
563  ++it)
564  for (const collision_detection::Contact& contact : it->second)
565  {
567  links.push_back(contact.body_name_1);
569  links.push_back(contact.body_name_2);
570  }
571 }
572 
573 const collision_detection::CollisionEnvPtr& PlanningScene::getCollisionEnvNonConst()
574 {
575  return active_collision_->cenv_;
576 }
577 
579 {
581  {
582  robot_state_ = std::make_shared<moveit::core::RobotState>(parent_->getCurrentState());
583  robot_state_->setAttachedBodyUpdateCallback(current_state_attached_body_callback_);
584  }
585  robot_state_->update();
586  return *robot_state_;
587 }
588 
589 moveit::core::RobotStatePtr PlanningScene::getCurrentStateUpdated(const moveit_msgs::RobotState& update) const
590 {
591  moveit::core::RobotStatePtr state(new moveit::core::RobotState(getCurrentState()));
593  return state;
594 }
595 
597 {
599  if (robot_state_)
600  robot_state_->setAttachedBodyUpdateCallback(callback);
601 }
602 
604 {
607  if (callback)
608  current_world_object_update_observer_handle_ = world_->addObserver(callback);
610 }
611 
613 {
614  if (!acm_)
615  acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(parent_->getAllowedCollisionMatrix());
616  return *acm_;
617 }
618 
620 {
621  // Trigger an update of the robot transforms
623  return static_cast<const PlanningScene*>(this)->getTransforms();
624 }
625 
627 {
628  // Trigger an update of the robot transforms
630  if (!scene_transforms_)
631  {
632  // The only case when there are no transforms is if this planning scene has a parent. When a non-const version of
633  // the planning scene is requested, a copy of the parent's transforms is forced
634  scene_transforms_ = std::make_shared<SceneTransforms>(this);
635  scene_transforms_->setAllTransforms(parent_->getTransforms().getAllTransforms());
636  }
637  return *scene_transforms_;
638 }
639 
640 void PlanningScene::getPlanningSceneDiffMsg(moveit_msgs::PlanningScene& scene_msg) const
641 {
642  scene_msg.name = name_;
643  scene_msg.robot_model_name = getRobotModel()->getName();
644  scene_msg.is_diff = true;
645 
646  if (scene_transforms_)
647  scene_transforms_->copyTransforms(scene_msg.fixed_frame_transforms);
648  else
649  scene_msg.fixed_frame_transforms.clear();
650 
651  if (robot_state_)
652  moveit::core::robotStateToRobotStateMsg(*robot_state_, scene_msg.robot_state);
653  else
654  scene_msg.robot_state = moveit_msgs::RobotState();
655  scene_msg.robot_state.is_diff = true;
656 
657  if (acm_)
658  acm_->getMessage(scene_msg.allowed_collision_matrix);
659  else
660  scene_msg.allowed_collision_matrix = moveit_msgs::AllowedCollisionMatrix();
661 
662  active_collision_->cenv_->getPadding(scene_msg.link_padding);
663  active_collision_->cenv_->getScale(scene_msg.link_scale);
664 
665  scene_msg.object_colors.clear();
666  if (object_colors_)
667  {
668  unsigned int i = 0;
669  scene_msg.object_colors.resize(object_colors_->size());
670  for (ObjectColorMap::const_iterator it = object_colors_->begin(); it != object_colors_->end(); ++it, ++i)
671  {
672  scene_msg.object_colors[i].id = it->first;
673  scene_msg.object_colors[i].color = it->second;
674  }
675  }
676 
677  scene_msg.world.collision_objects.clear();
678  scene_msg.world.octomap = octomap_msgs::OctomapWithPose();
679 
680  if (world_diff_)
681  {
682  bool do_omap = false;
683  for (const std::pair<const std::string, collision_detection::World::Action>& it : *world_diff_)
684  {
685  if (it.first == OCTOMAP_NS)
686  {
687  if (it.second == collision_detection::World::DESTROY)
688  scene_msg.world.octomap.octomap.id = "cleared"; // indicate cleared octomap
689  else
690  do_omap = true;
691  }
692  else if (it.second == collision_detection::World::DESTROY)
693  {
694  // if object became attached, it should not be recorded as removed here
695  if (!std::count_if(scene_msg.robot_state.attached_collision_objects.cbegin(),
696  scene_msg.robot_state.attached_collision_objects.cend(),
697  [&it](const moveit_msgs::AttachedCollisionObject& aco) {
698  return aco.object.id == it.first &&
699  aco.object.operation == moveit_msgs::CollisionObject::ADD;
700  }))
701  {
702  moveit_msgs::CollisionObject co;
703  co.header.frame_id = getPlanningFrame();
704  co.id = it.first;
705  co.operation = moveit_msgs::CollisionObject::REMOVE;
706  scene_msg.world.collision_objects.push_back(co);
707  }
708  }
709  else
710  {
711  scene_msg.world.collision_objects.emplace_back();
712  getCollisionObjectMsg(scene_msg.world.collision_objects.back(), it.first);
713  }
714  }
715  if (do_omap)
716  getOctomapMsg(scene_msg.world.octomap);
717  }
718 
719  // Ensure all detached collision objects actually get removed when applying the diff
720  // Because RobotState doesn't handle diffs (yet), we explicitly declare attached objects
721  // as removed, if they show up as "normal" collision objects but were attached in parent
722  for (const auto& collision_object : scene_msg.world.collision_objects)
723  {
724  if (parent_ && parent_->getCurrentState().hasAttachedBody(collision_object.id))
725  {
726  moveit_msgs::AttachedCollisionObject aco;
727  aco.object.id = collision_object.id;
728  aco.object.operation = moveit_msgs::CollisionObject::REMOVE;
729  scene_msg.robot_state.attached_collision_objects.push_back(aco);
730  }
731  }
732 }
733 
734 namespace
735 {
736 class ShapeVisitorAddToCollisionObject : public boost::static_visitor<void>
737 {
738 public:
739  ShapeVisitorAddToCollisionObject(moveit_msgs::CollisionObject* obj) : boost::static_visitor<void>(), obj_(obj)
740  {
741  }
742 
743  void setPoseMessage(const geometry_msgs::Pose* pose)
744  {
745  pose_ = pose;
746  }
747 
748  void operator()(const shape_msgs::Plane& shape_msg) const
749  {
750  obj_->planes.push_back(shape_msg);
751  obj_->plane_poses.push_back(*pose_);
752  }
753 
754  void operator()(const shape_msgs::Mesh& shape_msg) const
755  {
756  obj_->meshes.push_back(shape_msg);
757  obj_->mesh_poses.push_back(*pose_);
758  }
759 
760  void operator()(const shape_msgs::SolidPrimitive& shape_msg) const
761  {
762  obj_->primitives.push_back(shape_msg);
763  obj_->primitive_poses.push_back(*pose_);
764  }
765 
766 private:
767  moveit_msgs::CollisionObject* obj_;
768  const geometry_msgs::Pose* pose_;
769 };
770 } // namespace
771 
772 bool PlanningScene::getCollisionObjectMsg(moveit_msgs::CollisionObject& collision_obj, const std::string& ns) const
773 {
775  if (!obj)
776  return false;
777  collision_obj.header.frame_id = getPlanningFrame();
778  collision_obj.pose = tf2::toMsg(obj->pose_);
779  collision_obj.id = ns;
780  collision_obj.operation = moveit_msgs::CollisionObject::ADD;
781  ShapeVisitorAddToCollisionObject sv(&collision_obj);
782  for (std::size_t j = 0; j < obj->shapes_.size(); ++j)
783  {
784  shapes::ShapeMsg sm;
785  if (constructMsgFromShape(obj->shapes_[j].get(), sm))
786  {
787  geometry_msgs::Pose p = tf2::toMsg(obj->shape_poses_[j]);
788  sv.setPoseMessage(&p);
789  boost::apply_visitor(sv, sm);
790  }
791  }
792 
793  if (!collision_obj.primitives.empty() || !collision_obj.meshes.empty() || !collision_obj.planes.empty())
794  {
795  if (hasObjectType(collision_obj.id))
796  collision_obj.type = getObjectType(collision_obj.id);
797  }
798  for (const auto& frame_pair : obj->subframe_poses_)
799  {
800  collision_obj.subframe_names.push_back(frame_pair.first);
801  geometry_msgs::Pose p;
802  p = tf2::toMsg(frame_pair.second);
803  collision_obj.subframe_poses.push_back(p);
804  }
805 
806  return true;
807 }
808 
809 void PlanningScene::getCollisionObjectMsgs(std::vector<moveit_msgs::CollisionObject>& collision_objs) const
810 {
811  collision_objs.clear();
812  const std::vector<std::string>& ids = world_->getObjectIds();
813  for (const std::string& id : ids)
814  if (id != OCTOMAP_NS)
815  {
816  collision_objs.emplace_back();
817  getCollisionObjectMsg(collision_objs.back(), id);
818  }
819 }
820 
821 bool PlanningScene::getAttachedCollisionObjectMsg(moveit_msgs::AttachedCollisionObject& attached_collision_obj,
822  const std::string& ns) const
823 {
824  std::vector<moveit_msgs::AttachedCollisionObject> attached_collision_objs;
825  getAttachedCollisionObjectMsgs(attached_collision_objs);
826  for (moveit_msgs::AttachedCollisionObject& it : attached_collision_objs)
827  {
828  if (it.object.id == ns)
829  {
830  attached_collision_obj = it;
831  return true;
832  }
833  }
834  return false;
835 }
836 
838  std::vector<moveit_msgs::AttachedCollisionObject>& attached_collision_objs) const
839 {
840  std::vector<const moveit::core::AttachedBody*> attached_bodies;
841  getCurrentState().getAttachedBodies(attached_bodies);
842  attachedBodiesToAttachedCollisionObjectMsgs(attached_bodies, attached_collision_objs);
843 }
844 
845 bool PlanningScene::getOctomapMsg(octomap_msgs::OctomapWithPose& octomap) const
846 {
847  octomap.header.frame_id = getPlanningFrame();
848  octomap.octomap = octomap_msgs::Octomap();
849 
851  if (map)
852  {
853  if (map->shapes_.size() == 1)
854  {
855  const shapes::OcTree* o = static_cast<const shapes::OcTree*>(map->shapes_[0].get());
857  octomap.origin = tf2::toMsg(map->shape_poses_[0]);
858  return true;
859  }
860  ROS_ERROR_NAMED(LOGNAME, "Unexpected number of shapes in octomap collision object. Not including '%s' object",
861  OCTOMAP_NS.c_str());
862  }
863  return false;
864 }
865 
866 void PlanningScene::getObjectColorMsgs(std::vector<moveit_msgs::ObjectColor>& object_colors) const
867 {
868  object_colors.clear();
869 
870  unsigned int i = 0;
871  ObjectColorMap cmap;
872  getKnownObjectColors(cmap);
873  object_colors.resize(cmap.size());
874  for (ObjectColorMap::const_iterator it = cmap.begin(); it != cmap.end(); ++it, ++i)
875  {
876  object_colors[i].id = it->first;
877  object_colors[i].color = it->second;
878  }
879 }
880 
881 void PlanningScene::getPlanningSceneMsg(moveit_msgs::PlanningScene& scene_msg) const
882 {
883  scene_msg.name = name_;
884  scene_msg.is_diff = false;
885  scene_msg.robot_model_name = getRobotModel()->getName();
886  getTransforms().copyTransforms(scene_msg.fixed_frame_transforms);
887 
889  getAllowedCollisionMatrix().getMessage(scene_msg.allowed_collision_matrix);
890  getCollisionEnv()->getPadding(scene_msg.link_padding);
891  getCollisionEnv()->getScale(scene_msg.link_scale);
892 
893  getObjectColorMsgs(scene_msg.object_colors);
894 
895  // add collision objects
896  getCollisionObjectMsgs(scene_msg.world.collision_objects);
897 
898  // get the octomap
899  getOctomapMsg(scene_msg.world.octomap);
900 }
901 
902 void PlanningScene::getPlanningSceneMsg(moveit_msgs::PlanningScene& scene_msg,
903  const moveit_msgs::PlanningSceneComponents& comp) const
904 {
905  scene_msg.is_diff = false;
906  if (comp.components & moveit_msgs::PlanningSceneComponents::SCENE_SETTINGS)
907  {
908  scene_msg.name = name_;
909  scene_msg.robot_model_name = getRobotModel()->getName();
910  }
911 
912  if (comp.components & moveit_msgs::PlanningSceneComponents::TRANSFORMS)
913  getTransforms().copyTransforms(scene_msg.fixed_frame_transforms);
914 
915  if (comp.components & moveit_msgs::PlanningSceneComponents::ROBOT_STATE_ATTACHED_OBJECTS)
916  {
917  moveit::core::robotStateToRobotStateMsg(getCurrentState(), scene_msg.robot_state, true);
918  for (moveit_msgs::AttachedCollisionObject& attached_collision_object :
919  scene_msg.robot_state.attached_collision_objects)
920  {
921  if (hasObjectType(attached_collision_object.object.id))
922  {
923  attached_collision_object.object.type = getObjectType(attached_collision_object.object.id);
924  }
925  }
926  }
927  else if (comp.components & moveit_msgs::PlanningSceneComponents::ROBOT_STATE)
928  {
929  moveit::core::robotStateToRobotStateMsg(getCurrentState(), scene_msg.robot_state, false);
930  }
931 
932  if (comp.components & moveit_msgs::PlanningSceneComponents::ALLOWED_COLLISION_MATRIX)
933  getAllowedCollisionMatrix().getMessage(scene_msg.allowed_collision_matrix);
934 
935  if (comp.components & moveit_msgs::PlanningSceneComponents::LINK_PADDING_AND_SCALING)
936  {
937  getCollisionEnv()->getPadding(scene_msg.link_padding);
938  getCollisionEnv()->getScale(scene_msg.link_scale);
939  }
940 
941  if (comp.components & moveit_msgs::PlanningSceneComponents::OBJECT_COLORS)
942  getObjectColorMsgs(scene_msg.object_colors);
943 
944  // add collision objects
945  if (comp.components & moveit_msgs::PlanningSceneComponents::WORLD_OBJECT_GEOMETRY)
946  getCollisionObjectMsgs(scene_msg.world.collision_objects);
947  else if (comp.components & moveit_msgs::PlanningSceneComponents::WORLD_OBJECT_NAMES)
948  {
949  const std::vector<std::string>& ids = world_->getObjectIds();
950  scene_msg.world.collision_objects.clear();
951  scene_msg.world.collision_objects.reserve(ids.size());
952  for (const std::string& id : ids)
953  if (id != OCTOMAP_NS)
954  {
955  moveit_msgs::CollisionObject co;
956  co.id = id;
957  if (hasObjectType(co.id))
958  co.type = getObjectType(co.id);
959  scene_msg.world.collision_objects.push_back(co);
960  }
961  }
962 
963  // get the octomap
964  if (comp.components & moveit_msgs::PlanningSceneComponents::OCTOMAP)
965  getOctomapMsg(scene_msg.world.octomap);
966 }
967 
968 void PlanningScene::saveGeometryToStream(std::ostream& out) const
969 {
970  out << name_ << std::endl;
971  const std::vector<std::string>& ids = world_->getObjectIds();
972  for (const std::string& id : ids)
973  if (id != OCTOMAP_NS)
974  {
976  if (obj)
977  {
978  out << "* " << id << std::endl; // New object start
979  // Write object pose
980  writePoseToText(out, obj->pose_);
981 
982  // Write shapes and shape poses
983  out << obj->shapes_.size() << std::endl; // Number of shapes
984  for (std::size_t j = 0; j < obj->shapes_.size(); ++j)
985  {
986  shapes::saveAsText(obj->shapes_[j].get(), out);
987  // shape_poses_ is valid isometry by contract
988  writePoseToText(out, obj->shape_poses_[j]);
989  if (hasObjectColor(id))
990  {
991  const std_msgs::ColorRGBA& c = getObjectColor(id);
992  out << c.r << " " << c.g << " " << c.b << " " << c.a << std::endl;
993  }
994  else
995  out << "0 0 0 0" << std::endl;
996  }
997 
998  // Write subframes
999  out << obj->subframe_poses_.size() << std::endl; // Number of subframes
1000  for (auto& pose_pair : obj->subframe_poses_)
1001  {
1002  out << pose_pair.first << std::endl; // Subframe name
1003  writePoseToText(out, pose_pair.second); // Subframe pose
1004  }
1005  }
1006  }
1007  out << "." << std::endl;
1008 }
1009 
1010 bool PlanningScene::loadGeometryFromStream(std::istream& in)
1011 {
1012  return loadGeometryFromStream(in, Eigen::Isometry3d::Identity()); // Use no offset
1013 }
1014 
1015 bool PlanningScene::loadGeometryFromStream(std::istream& in, const Eigen::Isometry3d& offset)
1016 {
1017  if (!in.good() || in.eof())
1018  {
1019  ROS_ERROR_NAMED(LOGNAME, "Bad input stream when loading scene geometry");
1020  return false;
1021  }
1022  // Read scene name
1023  std::getline(in, name_);
1024 
1025  // Identify scene format version for backwards compatibility of parser
1026  auto pos = in.tellg(); // remember current stream position
1027  std::string line;
1028  do
1029  {
1030  std::getline(in, line);
1031  } while (in.good() && !in.eof() && (line.empty() || line[0] != '*')); // read * marker
1032  std::getline(in, line); // next line determines format
1033  boost::algorithm::trim(line);
1034  // new format: line specifies position of object, with spaces as delimiter -> spaces indicate new format
1035  // old format: line specifies number of shapes
1036  bool uses_new_scene_format = line.find(' ') != std::string::npos;
1037  in.seekg(pos);
1038 
1039  Eigen::Isometry3d pose; // Transient
1040  do
1041  {
1042  std::string marker;
1043  in >> marker;
1044  if (!in.good() || in.eof())
1045  {
1046  ROS_ERROR_NAMED(LOGNAME, "Bad input stream when loading marker in scene geometry");
1047  return false;
1048  }
1049  if (marker == "*") // Start of new object
1050  {
1051  std::string object_id;
1052  std::getline(in, object_id);
1053  if (!in.good() || in.eof())
1054  {
1055  ROS_ERROR_NAMED(LOGNAME, "Bad input stream when loading object_id in scene geometry");
1056  return false;
1057  }
1058  boost::algorithm::trim(object_id);
1059 
1060  // Read in object pose (added in the new scene format)
1061  pose.setIdentity();
1062  if (uses_new_scene_format && !readPoseFromText(in, pose))
1063  {
1064  ROS_ERROR_NAMED(LOGNAME, "Failed to read object pose from scene file");
1065  return false;
1066  }
1067  Eigen::Isometry3d object_pose = offset * pose; // Transform pose by input pose offset
1068 
1069  // Read in shapes
1070  unsigned int shape_count;
1071  in >> shape_count;
1072  if (shape_count) // If there are any shapes to be loaded, clear any existing object first
1073  world_->removeObject(object_id);
1074  for (std::size_t i = 0; i < shape_count && in.good() && !in.eof(); ++i)
1075  {
1076  const auto shape = shapes::ShapeConstPtr(shapes::constructShapeFromText(in));
1077  if (!shape)
1078  {
1079  ROS_ERROR_NAMED(LOGNAME, "Failed to load shape from scene file");
1080  return false;
1081  }
1082  if (!readPoseFromText(in, pose))
1083  {
1084  ROS_ERROR_NAMED(LOGNAME, "Failed to read pose from scene file");
1085  return false;
1086  }
1087  float r, g, b, a;
1088  if (!(in >> r >> g >> b >> a))
1089  {
1090  ROS_ERROR_NAMED(LOGNAME, "Improperly formatted color in scene geometry file");
1091  return false;
1092  }
1093  if (shape)
1094  {
1095  world_->addToObject(object_id, shape, pose);
1096  if (r > 0.0f || g > 0.0f || b > 0.0f || a > 0.0f)
1097  {
1098  std_msgs::ColorRGBA color;
1099  color.r = r;
1100  color.g = g;
1101  color.b = b;
1102  color.a = a;
1103  setObjectColor(object_id, color);
1104  }
1105  }
1106  }
1107 
1108  // Finally set object's pose once
1109  world_->setObjectPose(object_id, object_pose);
1110 
1111  // Read in subframes (added in the new scene format)
1112  if (uses_new_scene_format)
1113  {
1115  unsigned int subframe_count;
1116  in >> subframe_count;
1117  for (std::size_t i = 0; i < subframe_count && in.good() && !in.eof(); ++i)
1118  {
1119  std::string subframe_name;
1120  in >> subframe_name;
1121  if (!readPoseFromText(in, pose))
1122  {
1123  ROS_ERROR_NAMED(LOGNAME, "Failed to read subframe pose from scene file");
1124  return false;
1125  }
1126  subframes[subframe_name] = pose;
1127  }
1128  world_->setSubframesOfObject(object_id, subframes);
1129  }
1130  }
1131  else if (marker == ".")
1132  {
1133  // Marks the end of the scene geometry;
1134  return true;
1135  }
1136  else
1137  {
1138  ROS_ERROR_STREAM_NAMED(LOGNAME, "Unknown marker in scene geometry file: " << marker);
1139  return false;
1140  }
1141  } while (true);
1142 }
1143 
1144 bool PlanningScene::readPoseFromText(std::istream& in, Eigen::Isometry3d& pose) const
1145 {
1146  double x, y, z, rx, ry, rz, rw;
1147  if (!(in >> x >> y >> z))
1148  {
1149  ROS_ERROR_NAMED(LOGNAME, "Improperly formatted translation in scene geometry file");
1150  return false;
1151  }
1152  if (!(in >> rx >> ry >> rz >> rw))
1153  {
1154  ROS_ERROR_NAMED(LOGNAME, "Improperly formatted rotation in scene geometry file");
1155  return false;
1156  }
1157  pose = Eigen::Translation3d(x, y, z) * Eigen::Quaterniond(rw, rx, ry, rz);
1158  return true;
1159 }
1160 
1161 void PlanningScene::writePoseToText(std::ostream& out, const Eigen::Isometry3d& pose) const
1162 {
1163  out << pose.translation().x() << " " << pose.translation().y() << " " << pose.translation().z() << std::endl;
1164  Eigen::Quaterniond r(pose.linear());
1165  out << r.x() << " " << r.y() << " " << r.z() << " " << r.w() << std::endl;
1166 }
1167 
1168 void PlanningScene::setCurrentState(const moveit_msgs::RobotState& state)
1169 {
1170  // The attached bodies will be processed separately by processAttachedCollisionObjectMsgs
1171  // after robot_state_ has been updated
1172  moveit_msgs::RobotState state_no_attached(state);
1173  state_no_attached.attached_collision_objects.clear();
1174 
1175  if (parent_)
1176  {
1177  if (!robot_state_)
1178  {
1179  robot_state_ = std::make_shared<moveit::core::RobotState>(parent_->getCurrentState());
1180  robot_state_->setAttachedBodyUpdateCallback(current_state_attached_body_callback_);
1181  }
1183  }
1184  else
1186 
1187  for (std::size_t i = 0; i < state.attached_collision_objects.size(); ++i)
1188  {
1189  if (!state.is_diff && state.attached_collision_objects[i].object.operation != moveit_msgs::CollisionObject::ADD)
1190  {
1192  "The specified RobotState is not marked as is_diff. "
1193  "The request to modify the object '%s' is not supported. Object is ignored.",
1194  state.attached_collision_objects[i].object.id.c_str());
1195  continue;
1196  }
1197  processAttachedCollisionObjectMsg(state.attached_collision_objects[i]);
1198  }
1199 }
1202 {
1203  getCurrentStateNonConst() = state;
1204 }
1205 
1207 {
1208  if (!parent_)
1209  return;
1210 
1211  // This child planning scene did not have its own copy of frame transforms
1212  if (!scene_transforms_)
1213  {
1214  scene_transforms_ = std::make_shared<SceneTransforms>(this);
1215  scene_transforms_->setAllTransforms(parent_->getTransforms().getAllTransforms());
1216  }
1217 
1218  if (!robot_state_)
1219  {
1220  robot_state_ = std::make_shared<moveit::core::RobotState>(parent_->getCurrentState());
1221  robot_state_->setAttachedBodyUpdateCallback(current_state_attached_body_callback_);
1222  }
1223 
1224  if (!acm_)
1225  acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(parent_->getAllowedCollisionMatrix());
1226 
1227  for (std::pair<const std::string, CollisionDetectorPtr>& it : collision_)
1228  {
1229  it.second->parent_.reset();
1230  }
1231  world_diff_.reset();
1232 
1234  {
1235  ObjectColorMap kc;
1236  parent_->getKnownObjectColors(kc);
1237  object_colors_ = std::make_unique<ObjectColorMap>(kc);
1238  }
1239  else
1240  {
1241  ObjectColorMap kc;
1242  parent_->getKnownObjectColors(kc);
1243  for (ObjectColorMap::const_iterator it = kc.begin(); it != kc.end(); ++it)
1244  if (object_colors_->find(it->first) == object_colors_->end())
1245  (*object_colors_)[it->first] = it->second;
1246  }
1247 
1248  if (!object_types_)
1249  {
1250  ObjectTypeMap kc;
1251  parent_->getKnownObjectTypes(kc);
1252  object_types_ = std::make_unique<ObjectTypeMap>(kc);
1253  }
1254  else
1255  {
1256  ObjectTypeMap kc;
1257  parent_->getKnownObjectTypes(kc);
1258  for (ObjectTypeMap::const_iterator it = kc.begin(); it != kc.end(); ++it)
1259  if (object_types_->find(it->first) == object_types_->end())
1260  (*object_types_)[it->first] = it->second;
1261  }
1262 
1263  parent_.reset();
1264 }
1265 
1266 bool PlanningScene::setPlanningSceneDiffMsg(const moveit_msgs::PlanningScene& scene_msg)
1267 {
1268  bool result = true;
1269 
1270  ROS_DEBUG_NAMED(LOGNAME, "Adding planning scene diff");
1271  if (!scene_msg.name.empty())
1272  name_ = scene_msg.name;
1273 
1274  if (!scene_msg.robot_model_name.empty() && scene_msg.robot_model_name != getRobotModel()->getName())
1275  ROS_WARN_NAMED(LOGNAME, "Setting the scene for model '%s' but model '%s' is loaded.",
1276  scene_msg.robot_model_name.c_str(), getRobotModel()->getName().c_str());
1277 
1278  // there is at least one transform in the list of fixed transform: from model frame to itself;
1279  // if the list is empty, then nothing has been set
1280  if (!scene_msg.fixed_frame_transforms.empty())
1281  {
1282  if (!scene_transforms_)
1283  scene_transforms_ = std::make_shared<SceneTransforms>(this);
1284  scene_transforms_->setTransforms(scene_msg.fixed_frame_transforms);
1285  }
1286 
1287  // if at least some joints have been specified, we set them
1288  if (!scene_msg.robot_state.multi_dof_joint_state.joint_names.empty() ||
1289  !scene_msg.robot_state.joint_state.name.empty() || !scene_msg.robot_state.attached_collision_objects.empty())
1290  setCurrentState(scene_msg.robot_state);
1291 
1292  // if at least some links are mentioned in the allowed collision matrix, then we have an update
1293  if (!scene_msg.allowed_collision_matrix.entry_names.empty())
1294  acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(scene_msg.allowed_collision_matrix);
1295 
1296  if (!scene_msg.link_padding.empty() || !scene_msg.link_scale.empty())
1297  {
1298  for (std::pair<const std::string, CollisionDetectorPtr>& it : collision_)
1299  {
1300  it.second->cenv_->setPadding(scene_msg.link_padding);
1301  it.second->cenv_->setScale(scene_msg.link_scale);
1302  }
1303  }
1304 
1305  // if any colors have been specified, replace the ones we have with the specified ones
1306  for (const moveit_msgs::ObjectColor& object_color : scene_msg.object_colors)
1307  setObjectColor(object_color.id, object_color.color);
1308 
1309  // process collision object updates
1310  for (const moveit_msgs::CollisionObject& collision_object : scene_msg.world.collision_objects)
1311  result &= processCollisionObjectMsg(collision_object);
1312 
1313  // if an octomap was specified, replace the one we have with that one
1314  if (!scene_msg.world.octomap.octomap.id.empty())
1315  processOctomapMsg(scene_msg.world.octomap);
1316 
1317  return result;
1318 }
1319 
1320 bool PlanningScene::setPlanningSceneMsg(const moveit_msgs::PlanningScene& scene_msg)
1321 {
1322  assert(scene_msg.is_diff == false);
1323  ROS_DEBUG_NAMED(LOGNAME, "Setting new planning scene: '%s'", scene_msg.name.c_str());
1324  name_ = scene_msg.name;
1325 
1326  if (!scene_msg.robot_model_name.empty() && scene_msg.robot_model_name != getRobotModel()->getName())
1327  ROS_WARN_NAMED(LOGNAME, "Setting the scene for model '%s' but model '%s' is loaded.",
1328  scene_msg.robot_model_name.c_str(), getRobotModel()->getName().c_str());
1329 
1330  if (parent_)
1331  decoupleParent();
1332 
1333  object_types_.reset();
1334  scene_transforms_->setTransforms(scene_msg.fixed_frame_transforms);
1335  setCurrentState(scene_msg.robot_state);
1336  acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(scene_msg.allowed_collision_matrix);
1337  for (std::pair<const std::string, CollisionDetectorPtr>& it : collision_)
1338  {
1339  it.second->cenv_->setPadding(scene_msg.link_padding);
1340  it.second->cenv_->setScale(scene_msg.link_scale);
1341  }
1342  object_colors_ = std::make_unique<ObjectColorMap>();
1343  for (const moveit_msgs::ObjectColor& object_color : scene_msg.object_colors)
1344  setObjectColor(object_color.id, object_color.color);
1345  world_->clearObjects();
1346  return processPlanningSceneWorldMsg(scene_msg.world);
1347 }
1348 
1349 bool PlanningScene::processPlanningSceneWorldMsg(const moveit_msgs::PlanningSceneWorld& world)
1350 {
1351  bool result = true;
1352  for (const moveit_msgs::CollisionObject& collision_object : world.collision_objects)
1353  result &= processCollisionObjectMsg(collision_object);
1354  processOctomapMsg(world.octomap);
1355  return result;
1356 }
1357 
1358 bool PlanningScene::usePlanningSceneMsg(const moveit_msgs::PlanningScene& scene_msg)
1359 {
1360  if (scene_msg.is_diff)
1361  return setPlanningSceneDiffMsg(scene_msg);
1362  else
1363  return setPlanningSceneMsg(scene_msg);
1364 }
1365 
1366 collision_detection::OccMapTreePtr createOctomap(const octomap_msgs::Octomap& map)
1367 {
1368  std::shared_ptr<collision_detection::OccMapTree> om =
1369  std::make_shared<collision_detection::OccMapTree>(map.resolution);
1370  if (map.binary)
1371  {
1372  octomap_msgs::readTree(om.get(), map);
1373  }
1374  else
1375  {
1376  std::stringstream datastream;
1377  if (!map.data.empty())
1378  {
1379  datastream.write((const char*)&map.data[0], map.data.size());
1380  om->readData(datastream);
1381  }
1382  }
1383  return om;
1384 }
1385 
1386 void PlanningScene::processOctomapMsg(const octomap_msgs::Octomap& map)
1387 {
1388  // each octomap replaces any previous one
1389  world_->removeObject(OCTOMAP_NS);
1391  if (map.data.empty())
1392  return;
1393 
1394  if (map.id != "OcTree")
1395  {
1396  ROS_ERROR_NAMED(LOGNAME, "Received octomap is of type '%s' but type 'OcTree' is expected.", map.id.c_str());
1397  return;
1398  }
1399 
1400  std::shared_ptr<collision_detection::OccMapTree> om = createOctomap(map);
1401  if (!map.header.frame_id.empty())
1402  {
1403  const Eigen::Isometry3d& t = getFrameTransform(map.header.frame_id);
1404  world_->addToObject(OCTOMAP_NS, shapes::ShapeConstPtr(new shapes::OcTree(om)), t);
1405  }
1406  else
1407  {
1408  world_->addToObject(OCTOMAP_NS, shapes::ShapeConstPtr(new shapes::OcTree(om)), Eigen::Isometry3d::Identity());
1409  }
1410 }
1411 
1413 {
1414  const std::vector<std::string>& object_ids = world_->getObjectIds();
1415  for (const std::string& object_id : object_ids)
1416  if (object_id != OCTOMAP_NS)
1417  {
1418  world_->removeObject(object_id);
1419  removeObjectColor(object_id);
1420  removeObjectType(object_id);
1422  }
1423 }
1424 
1425 void PlanningScene::processOctomapMsg(const octomap_msgs::OctomapWithPose& map)
1426 {
1427  // each octomap replaces any previous one
1428  world_->removeObject(OCTOMAP_NS);
1429 
1430  if (map.octomap.data.empty())
1431  return;
1432 
1433  if (map.octomap.id != "OcTree")
1434  {
1435  ROS_ERROR_NAMED(LOGNAME, "Received octomap is of type '%s' but type 'OcTree' is expected.", map.octomap.id.c_str());
1436  return;
1437  }
1438 
1439  std::shared_ptr<collision_detection::OccMapTree> om = createOctomap(map.octomap);
1440 
1441  const Eigen::Isometry3d& t = getFrameTransform(map.header.frame_id);
1442  Eigen::Isometry3d p;
1443  PlanningScene::poseMsgToEigen(map.origin, p);
1444  p = t * p;
1445  world_->addToObject(OCTOMAP_NS, shapes::ShapeConstPtr(new shapes::OcTree(om)), p);
1446 }
1447 
1448 void PlanningScene::processOctomapPtr(const std::shared_ptr<const octomap::OcTree>& octree, const Eigen::Isometry3d& t)
1449 {
1451  if (map)
1452  {
1453  if (map->shapes_.size() == 1)
1454  {
1455  // check to see if we have the same octree pointer & pose.
1456  const shapes::OcTree* o = static_cast<const shapes::OcTree*>(map->shapes_[0].get());
1457  if (o->octree == octree)
1458  {
1459  // if the pose changed, we update it
1460  if (map->shape_poses_[0].isApprox(t, std::numeric_limits<double>::epsilon() * 100.0))
1461  {
1462  if (world_diff_)
1465  }
1466  else
1467  {
1468  shapes::ShapeConstPtr shape = map->shapes_[0];
1469  map.reset(); // reset this pointer first so that caching optimizations can be used in CollisionWorld
1470  world_->moveShapeInObject(OCTOMAP_NS, shape, t);
1471  }
1472  return;
1473  }
1474  }
1475  }
1476  // if the octree pointer changed, update the structure
1477  world_->removeObject(OCTOMAP_NS);
1478  world_->addToObject(OCTOMAP_NS, shapes::ShapeConstPtr(new shapes::OcTree(octree)), t);
1479 }
1481 bool PlanningScene::processAttachedCollisionObjectMsg(const moveit_msgs::AttachedCollisionObject& object)
1482 {
1483  if (object.object.operation == moveit_msgs::CollisionObject::ADD && !getRobotModel()->hasLinkModel(object.link_name))
1484  {
1485  ROS_ERROR_NAMED(LOGNAME, "Unable to attach a body to link '%s' (link not found)", object.link_name.c_str());
1486  return false;
1487  }
1488 
1489  if (object.object.id == OCTOMAP_NS)
1490  {
1491  ROS_ERROR_NAMED(LOGNAME, "The ID '%s' cannot be used for collision objects (name reserved)", OCTOMAP_NS.c_str());
1492  return false;
1493  }
1494 
1495  if (!robot_state_) // there must be a parent in this case
1496  {
1497  robot_state_ = std::make_shared<moveit::core::RobotState>(parent_->getCurrentState());
1498  robot_state_->setAttachedBodyUpdateCallback(current_state_attached_body_callback_);
1499  }
1500  robot_state_->update();
1501 
1502  // The ADD/REMOVE operations follow this order:
1503  // STEP 1: Get info about the object from either the message or the world/RobotState
1504  // STEP 2: Remove the object from the world/RobotState if necessary
1505  // STEP 3: Put the object in the RobotState/world
1506 
1507  if (object.object.operation == moveit_msgs::CollisionObject::ADD ||
1508  object.object.operation == moveit_msgs::CollisionObject::APPEND)
1509  {
1510  const moveit::core::LinkModel* link_model = getRobotModel()->getLinkModel(object.link_name);
1511  if (link_model)
1512  {
1513  // items to build the attached object from (filled from existing world object or message)
1514  Eigen::Isometry3d object_pose_in_link;
1515  std::vector<shapes::ShapeConstPtr> shapes;
1516  EigenSTL::vector_Isometry3d shape_poses;
1517  moveit::core::FixedTransformsMap subframe_poses;
1518 
1519  // STEP 1: Obtain info about object to be attached.
1520  // If it is in the world, message contents are ignored.
1521 
1522  collision_detection::CollisionEnv::ObjectConstPtr obj_in_world = world_->getObject(object.object.id);
1523  if (object.object.operation == moveit_msgs::CollisionObject::ADD && object.object.primitives.empty() &&
1524  object.object.meshes.empty() && object.object.planes.empty())
1525  {
1526  if (obj_in_world)
1527  {
1528  ROS_DEBUG_NAMED(LOGNAME, "Attaching world object '%s' to link '%s'", object.object.id.c_str(),
1529  object.link_name.c_str());
1530  object_pose_in_link = robot_state_->getGlobalLinkTransform(link_model).inverse() * obj_in_world->pose_;
1531  shapes = obj_in_world->shapes_;
1532  shape_poses = obj_in_world->shape_poses_;
1533  subframe_poses = obj_in_world->subframe_poses_;
1534  }
1535  else
1536  {
1538  "Attempting to attach object '%s' to link '%s' but no geometry specified "
1539  "and such an object does not exist in the collision world",
1540  object.object.id.c_str(), object.link_name.c_str());
1541  return false;
1542  }
1543  }
1544  else // If object is not in the world, use the message contents
1545  {
1546  Eigen::Isometry3d header_frame_to_object_pose;
1547  if (!shapesAndPosesFromCollisionObjectMessage(object.object, header_frame_to_object_pose, shapes, shape_poses))
1548  return false;
1549  const Eigen::Isometry3d world_to_header_frame = getFrameTransform(object.object.header.frame_id);
1550  const Eigen::Isometry3d link_to_header_frame =
1551  robot_state_->getGlobalLinkTransform(link_model).inverse() * world_to_header_frame;
1552  object_pose_in_link = link_to_header_frame * header_frame_to_object_pose;
1553 
1554  Eigen::Isometry3d subframe_pose;
1555  for (std::size_t i = 0; i < object.object.subframe_poses.size(); ++i)
1556  {
1557  PlanningScene::poseMsgToEigen(object.object.subframe_poses[i], subframe_pose);
1558  std::string name = object.object.subframe_names[i];
1559  subframe_poses[name] = subframe_pose;
1560  }
1561  }
1562 
1563  if (shapes.empty())
1564  {
1565  ROS_ERROR_NAMED(LOGNAME, "There is no geometry to attach to link '%s' as part of attached body '%s'",
1566  object.link_name.c_str(), object.object.id.c_str());
1567  return false;
1568  }
1569 
1570  if (!object.object.type.db.empty() || !object.object.type.key.empty())
1571  setObjectType(object.object.id, object.object.type);
1572 
1573  // STEP 2: Remove the object from the world (if it existed)
1574  if (obj_in_world && world_->removeObject(object.object.id))
1575  {
1576  if (object.object.operation == moveit_msgs::CollisionObject::ADD)
1577  ROS_DEBUG_NAMED(LOGNAME, "Removing world object with the same name as newly attached object: '%s'",
1578  object.object.id.c_str());
1579  else
1581  "You tried to append geometry to an attached object "
1582  "that is actually a world object ('%s'). World geometry is ignored.",
1583  object.object.id.c_str());
1584  }
1585 
1586  // STEP 3: Attach the object to the robot
1587  if (object.object.operation == moveit_msgs::CollisionObject::ADD ||
1588  !robot_state_->hasAttachedBody(object.object.id))
1589  {
1590  if (robot_state_->clearAttachedBody(object.object.id))
1592  "The robot state already had an object named '%s' attached to link '%s'. "
1593  "The object was replaced.",
1594  object.object.id.c_str(), object.link_name.c_str());
1595 
1596  robot_state_->attachBody(object.object.id, object_pose_in_link, shapes, shape_poses, object.touch_links,
1597  object.link_name, object.detach_posture, subframe_poses);
1598  ROS_DEBUG_NAMED(LOGNAME, "Attached object '%s' to link '%s'", object.object.id.c_str(),
1599  object.link_name.c_str());
1600  }
1601  else // APPEND: augment to existing attached object
1602  {
1603  const moveit::core::AttachedBody* ab = robot_state_->getAttachedBody(object.object.id);
1604 
1605  // Allow overriding the body's pose if provided, otherwise keep the old one
1606  if (moveit::core::isEmpty(object.object.pose))
1607  object_pose_in_link = ab->getPose(); // Keep old pose
1608 
1609  shapes.insert(shapes.end(), ab->getShapes().begin(), ab->getShapes().end());
1610  shape_poses.insert(shape_poses.end(), ab->getShapePoses().begin(), ab->getShapePoses().end());
1611  subframe_poses.insert(ab->getSubframes().begin(), ab->getSubframes().end());
1612  trajectory_msgs::JointTrajectory detach_posture =
1613  object.detach_posture.joint_names.empty() ? ab->getDetachPosture() : object.detach_posture;
1614 
1615  std::set<std::string> touch_links = ab->getTouchLinks();
1616  touch_links.insert(std::make_move_iterator(object.touch_links.begin()),
1617  std::make_move_iterator(object.touch_links.end()));
1618 
1619  robot_state_->clearAttachedBody(object.object.id);
1620  robot_state_->attachBody(object.object.id, object_pose_in_link, shapes, shape_poses, touch_links,
1621  object.link_name, detach_posture, subframe_poses);
1622  ROS_DEBUG_NAMED(LOGNAME, "Appended things to object '%s' attached to link '%s'", object.object.id.c_str(),
1623  object.link_name.c_str());
1624  }
1625  return true;
1626  }
1627  else
1628  ROS_ERROR_NAMED(LOGNAME, "Robot state is not compatible with robot model. This could be fatal.");
1629  }
1630  else if (object.object.operation == moveit_msgs::CollisionObject::REMOVE) // == DETACH
1631  {
1632  // STEP 1: Get info about the object from the RobotState
1633  std::vector<const moveit::core::AttachedBody*> attached_bodies;
1634  if (object.object.id.empty())
1635  {
1636  const moveit::core::LinkModel* link_model =
1637  object.link_name.empty() ? nullptr : getRobotModel()->getLinkModel(object.link_name);
1638  if (link_model) // if we have a link model specified, only fetch bodies attached to this link
1639  robot_state_->getAttachedBodies(attached_bodies, link_model);
1640  else
1641  robot_state_->getAttachedBodies(attached_bodies);
1642  }
1643  else // A specific object id will be removed.
1644  {
1645  const moveit::core::AttachedBody* body = robot_state_->getAttachedBody(object.object.id);
1646  if (body)
1647  {
1648  if (!object.link_name.empty() && (body->getAttachedLinkName() != object.link_name))
1649  {
1650  ROS_ERROR_STREAM_NAMED(LOGNAME, "The AttachedCollisionObject message states the object is attached to "
1651  << object.link_name << ", but it is actually attached to "
1652  << body->getAttachedLinkName()
1653  << ". Leave the link_name empty or specify the correct link.");
1654  return false;
1655  }
1656  attached_bodies.push_back(body);
1657  }
1658  }
1659 
1660  // STEP 2+3: Remove the attached object(s) from the RobotState and put them in the world
1661  for (const moveit::core::AttachedBody* attached_body : attached_bodies)
1662  {
1663  const std::string& name = attached_body->getName();
1664  if (world_->hasObject(name))
1666  "The collision world already has an object with the same name as the body about to be detached. "
1667  "NOT adding the detached body '%s' to the collision world.",
1668  object.object.id.c_str());
1669  else
1670  {
1671  const Eigen::Isometry3d& pose = attached_body->getGlobalPose();
1672  world_->addToObject(name, pose, attached_body->getShapes(), attached_body->getShapePoses());
1673  world_->setSubframesOfObject(name, attached_body->getSubframes());
1674  ROS_DEBUG_NAMED(LOGNAME, "Detached object '%s' from link '%s' and added it back in the collision world",
1675  name.c_str(), object.link_name.c_str());
1676  }
1677 
1678  robot_state_->clearAttachedBody(name);
1679  }
1680  if (!attached_bodies.empty() || object.object.id.empty())
1681  return true;
1682  }
1683  else if (object.object.operation == moveit_msgs::CollisionObject::MOVE)
1684  {
1685  ROS_ERROR_NAMED(LOGNAME, "Move for attached objects not yet implemented");
1686  }
1687  else
1688  {
1689  ROS_ERROR_NAMED(LOGNAME, "Unknown collision object operation: %d", object.object.operation);
1690  }
1691 
1692  return false;
1693 }
1694 
1695 bool PlanningScene::processCollisionObjectMsg(const moveit_msgs::CollisionObject& object)
1696 {
1697  if (object.id == OCTOMAP_NS)
1698  {
1699  ROS_ERROR_NAMED(LOGNAME, "The ID '%s' cannot be used for collision objects (name reserved)", OCTOMAP_NS.c_str());
1700  return false;
1701  }
1702 
1703  if (object.operation == moveit_msgs::CollisionObject::ADD || object.operation == moveit_msgs::CollisionObject::APPEND)
1704  {
1705  return processCollisionObjectAdd(object);
1706  }
1707  else if (object.operation == moveit_msgs::CollisionObject::REMOVE)
1708  {
1709  return processCollisionObjectRemove(object);
1710  }
1711  else if (object.operation == moveit_msgs::CollisionObject::MOVE)
1712  {
1713  return processCollisionObjectMove(object);
1714  }
1715 
1716  ROS_ERROR_NAMED(LOGNAME, "Unknown collision object operation: %d", object.operation);
1717  return false;
1718 }
1719 
1720 void PlanningScene::poseMsgToEigen(const geometry_msgs::Pose& msg, Eigen::Isometry3d& out)
1721 {
1722  Eigen::Translation3d translation(msg.position.x, msg.position.y, msg.position.z);
1723  Eigen::Quaterniond quaternion(msg.orientation.w, msg.orientation.x, msg.orientation.y, msg.orientation.z);
1724  if ((quaternion.x() == 0) && (quaternion.y() == 0) && (quaternion.z() == 0) && (quaternion.w() == 0))
1725  {
1726  ROS_WARN_NAMED(LOGNAME, "Empty quaternion found in pose message. Setting to neutral orientation.");
1727  quaternion.setIdentity();
1728  }
1729  else
1730  {
1731  quaternion.normalize();
1732  }
1733  out = translation * quaternion;
1734 }
1735 
1736 bool PlanningScene::shapesAndPosesFromCollisionObjectMessage(const moveit_msgs::CollisionObject& object,
1737  Eigen::Isometry3d& object_pose,
1738  std::vector<shapes::ShapeConstPtr>& shapes,
1739  EigenSTL::vector_Isometry3d& shape_poses)
1740 {
1741  if (object.primitives.size() < object.primitive_poses.size())
1742  {
1743  ROS_ERROR_NAMED(LOGNAME, "More primitive shape poses than shapes in collision object message.");
1744  return false;
1745  }
1746  if (object.meshes.size() < object.mesh_poses.size())
1747  {
1748  ROS_ERROR_NAMED(LOGNAME, "More mesh poses than meshes in collision object message.");
1749  return false;
1750  }
1751  if (object.planes.size() < object.plane_poses.size())
1752  {
1753  ROS_ERROR_NAMED(LOGNAME, "More plane poses than planes in collision object message.");
1754  return false;
1755  }
1756 
1757  const int num_shapes = object.primitives.size() + object.meshes.size() + object.planes.size();
1758  shapes.reserve(num_shapes);
1759  shape_poses.reserve(num_shapes);
1760 
1761  bool switch_object_pose_and_shape_pose = false;
1762  if (num_shapes == 1 && moveit::core::isEmpty(object.pose))
1763  {
1764  // If the object pose is not set but the shape pose is, use the shape's pose as the object pose.
1765  switch_object_pose_and_shape_pose = true;
1766  object_pose.setIdentity();
1767  }
1768  else
1769  PlanningScene::poseMsgToEigen(object.pose, object_pose);
1770 
1771  auto append = [&object_pose, &shapes, &shape_poses,
1772  &switch_object_pose_and_shape_pose](shapes::Shape* s, const geometry_msgs::Pose& pose_msg) {
1773  if (!s)
1774  return;
1775  Eigen::Isometry3d pose;
1776  PlanningScene::poseMsgToEigen(pose_msg, pose);
1777  if (!switch_object_pose_and_shape_pose)
1778  shape_poses.emplace_back(std::move(pose));
1779  else
1780  {
1781  shape_poses.emplace_back(std::move(object_pose));
1782  object_pose = pose;
1783  }
1784  shapes.emplace_back(shapes::ShapeConstPtr(s));
1785  };
1786 
1787  auto treat_shape_vectors = [&append](const auto& shape_vector, // the shape_msgs of each type
1788  const auto& shape_poses_vector, // std::vector<const geometry_msgs::Pose>
1789  const std::string& shape_type) {
1790  if (shape_vector.size() > shape_poses_vector.size())
1791  {
1792  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Number of " << shape_type
1793  << " does not match number of poses "
1794  "in collision object message. Assuming identity.");
1795  for (std::size_t i = 0; i < shape_vector.size(); ++i)
1796  {
1797  if (i >= shape_poses_vector.size())
1798  {
1799  // Empty shape pose => Identity
1800  geometry_msgs::Pose identity;
1801  identity.orientation.w = 1.0;
1802  append(shapes::constructShapeFromMsg(shape_vector[i]), identity);
1803  }
1804  else
1805  append(shapes::constructShapeFromMsg(shape_vector[i]), shape_poses_vector[i]);
1806  }
1807  }
1808  else
1809  for (std::size_t i = 0; i < shape_vector.size(); ++i)
1810  append(shapes::constructShapeFromMsg(shape_vector[i]), shape_poses_vector[i]);
1811  };
1812 
1813  treat_shape_vectors(object.primitives, object.primitive_poses, std::string("primitive_poses"));
1814  treat_shape_vectors(object.meshes, object.mesh_poses, std::string("meshes"));
1815  treat_shape_vectors(object.planes, object.plane_poses, std::string("planes"));
1816  return true;
1817 }
1818 
1819 bool PlanningScene::processCollisionObjectAdd(const moveit_msgs::CollisionObject& object)
1820 {
1821  if (!knowsFrameTransform(object.header.frame_id))
1822  {
1823  ROS_ERROR_STREAM_NAMED(LOGNAME, "Unknown frame: " << object.header.frame_id);
1824  return false;
1825  }
1826 
1827  if (object.primitives.empty() && object.meshes.empty() && object.planes.empty())
1828  {
1829  ROS_ERROR_NAMED(LOGNAME, "There are no shapes specified in the collision object message");
1830  return false;
1831  }
1832 
1833  // replace the object if ADD is specified instead of APPEND
1834  if (object.operation == moveit_msgs::CollisionObject::ADD && world_->hasObject(object.id))
1835  world_->removeObject(object.id);
1836 
1837  const Eigen::Isometry3d& world_to_object_header_transform = getFrameTransform(object.header.frame_id);
1838  Eigen::Isometry3d header_to_pose_transform;
1839  std::vector<shapes::ShapeConstPtr> shapes;
1840  EigenSTL::vector_Isometry3d shape_poses;
1841  if (!shapesAndPosesFromCollisionObjectMessage(object, header_to_pose_transform, shapes, shape_poses))
1842  return false;
1843  const Eigen::Isometry3d object_frame_transform = world_to_object_header_transform * header_to_pose_transform;
1844 
1845  world_->addToObject(object.id, object_frame_transform, shapes, shape_poses);
1846 
1847  if (!object.type.key.empty() || !object.type.db.empty())
1848  setObjectType(object.id, object.type);
1849 
1850  // Add subframes
1852  Eigen::Isometry3d subframe_pose;
1853  for (std::size_t i = 0; i < object.subframe_poses.size(); ++i)
1854  {
1855  PlanningScene::poseMsgToEigen(object.subframe_poses[i], subframe_pose);
1856  std::string name = object.subframe_names[i];
1857  subframes[name] = subframe_pose;
1858  }
1859  world_->setSubframesOfObject(object.id, subframes);
1860  return true;
1861 }
1862 
1863 bool PlanningScene::processCollisionObjectRemove(const moveit_msgs::CollisionObject& object)
1864 {
1865  if (object.id.empty())
1866  {
1868  }
1869  else
1870  {
1871  if (!world_->removeObject(object.id))
1872  {
1874  "Tried to remove world object '" << object.id << "', but it does not exist in this scene.");
1875  return false;
1876  }
1877 
1878  removeObjectColor(object.id);
1879  removeObjectType(object.id);
1881  }
1882  return true;
1883 }
1884 
1885 bool PlanningScene::processCollisionObjectMove(const moveit_msgs::CollisionObject& object)
1886 {
1887  if (world_->hasObject(object.id))
1888  {
1889  // update object pose
1890  if (!object.primitives.empty() || !object.meshes.empty() || !object.planes.empty())
1891  ROS_WARN_NAMED(LOGNAME, "Move operation for object '%s' ignores the geometry specified in the message.",
1892  object.id.c_str());
1893 
1894  const Eigen::Isometry3d& world_to_object_header_transform = getFrameTransform(object.header.frame_id);
1895  Eigen::Isometry3d header_to_pose_transform;
1896 
1897  PlanningScene::poseMsgToEigen(object.pose, header_to_pose_transform);
1898 
1899  const Eigen::Isometry3d object_frame_transform = world_to_object_header_transform * header_to_pose_transform;
1900  world_->setObjectPose(object.id, object_frame_transform);
1901 
1902  // update shape poses
1903  if (!object.primitive_poses.empty() || !object.mesh_poses.empty() || !object.plane_poses.empty())
1904  {
1905  auto world_object = world_->getObject(object.id); // object exists, checked earlier
1906 
1907  std::size_t shape_size = object.primitive_poses.size() + object.mesh_poses.size() + object.plane_poses.size();
1908  if (shape_size != world_object->shape_poses_.size())
1909  {
1910  ROS_ERROR_NAMED(LOGNAME, "Move operation for object '%s' must have same number of geometry poses. Cannot move.",
1911  object.id.c_str());
1912  return false;
1913  }
1914 
1915  // order matters -> primitive, mesh and plane
1916  EigenSTL::vector_Isometry3d shape_poses;
1917  for (const auto& shape_pose : object.primitive_poses)
1918  {
1919  shape_poses.emplace_back();
1920  PlanningScene::poseMsgToEigen(shape_pose, shape_poses.back());
1921  }
1922  for (const auto& shape_pose : object.mesh_poses)
1923  {
1924  shape_poses.emplace_back();
1925  PlanningScene::poseMsgToEigen(shape_pose, shape_poses.back());
1926  }
1927  for (const auto& shape_pose : object.plane_poses)
1928  {
1929  shape_poses.emplace_back();
1930  PlanningScene::poseMsgToEigen(shape_pose, shape_poses.back());
1931  }
1932 
1933  if (!world_->moveShapesInObject(object.id, shape_poses))
1934  {
1935  ROS_ERROR_NAMED(LOGNAME, "Move operation for object '%s' internal world error. Cannot move.", object.id.c_str());
1936  return false;
1937  }
1938  }
1939 
1940  return true;
1941  }
1942 
1943  ROS_ERROR_NAMED(LOGNAME, "World object '%s' does not exist. Cannot move.", object.id.c_str());
1944  return false;
1945 }
1946 
1947 const Eigen::Isometry3d& PlanningScene::getFrameTransform(const std::string& frame_id) const
1948 {
1949  return getFrameTransform(getCurrentState(), frame_id);
1950 }
1951 
1952 const Eigen::Isometry3d& PlanningScene::getFrameTransform(const std::string& frame_id)
1953 {
1954  if (getCurrentState().dirtyLinkTransforms())
1955  return getFrameTransform(getCurrentStateNonConst(), frame_id);
1956  else
1957  return getFrameTransform(getCurrentState(), frame_id);
1958 }
1959 
1960 const Eigen::Isometry3d& PlanningScene::getFrameTransform(const moveit::core::RobotState& state,
1961  const std::string& frame_id) const
1962 {
1963  if (!frame_id.empty() && frame_id[0] == '/')
1964  // Recursively call itself without the slash in front of frame name
1965  return getFrameTransform(frame_id.substr(1));
1966 
1967  bool frame_found;
1968  const Eigen::Isometry3d& t1 = state.getFrameTransform(frame_id, &frame_found);
1969  if (frame_found)
1970  return t1;
1971 
1972  const Eigen::Isometry3d& t2 = getWorld()->getTransform(frame_id, frame_found);
1973  if (frame_found)
1974  return t2;
1975  return getTransforms().Transforms::getTransform(frame_id);
1976 }
1977 
1978 bool PlanningScene::knowsFrameTransform(const std::string& frame_id) const
1980  return knowsFrameTransform(getCurrentState(), frame_id);
1981 }
1982 
1983 bool PlanningScene::knowsFrameTransform(const moveit::core::RobotState& state, const std::string& frame_id) const
1985  if (!frame_id.empty() && frame_id[0] == '/')
1986  return knowsFrameTransform(frame_id.substr(1));
1987 
1988  if (state.knowsFrameTransform(frame_id))
1989  return true;
1990  if (getWorld()->knowsTransform(frame_id))
1991  return true;
1992  return getTransforms().Transforms::canTransform(frame_id);
1993 }
1994 
1995 bool PlanningScene::hasObjectType(const std::string& object_id) const
1996 {
1997  if (object_types_)
1998  if (object_types_->find(object_id) != object_types_->end())
1999  return true;
2000  if (parent_)
2001  return parent_->hasObjectType(object_id);
2002  return false;
2003 }
2004 
2005 const object_recognition_msgs::ObjectType& PlanningScene::getObjectType(const std::string& object_id) const
2006 {
2007  if (object_types_)
2008  {
2009  ObjectTypeMap::const_iterator it = object_types_->find(object_id);
2010  if (it != object_types_->end())
2011  return it->second;
2012  }
2013  if (parent_)
2014  return parent_->getObjectType(object_id);
2015  static const object_recognition_msgs::ObjectType EMPTY;
2016  return EMPTY;
2017 }
2018 
2019 void PlanningScene::setObjectType(const std::string& object_id, const object_recognition_msgs::ObjectType& type)
2020 {
2021  if (!object_types_)
2022  object_types_ = std::make_unique<ObjectTypeMap>();
2023  (*object_types_)[object_id] = type;
2024 }
2025 
2026 void PlanningScene::removeObjectType(const std::string& object_id)
2028  if (object_types_)
2029  object_types_->erase(object_id);
2030 }
2031 
2033 {
2034  kc.clear();
2035  if (parent_)
2036  parent_->getKnownObjectTypes(kc);
2038  for (ObjectTypeMap::const_iterator it = object_types_->begin(); it != object_types_->end(); ++it)
2039  kc[it->first] = it->second;
2040 }
2041 
2042 bool PlanningScene::hasObjectColor(const std::string& object_id) const
2043 {
2044  if (object_colors_)
2045  if (object_colors_->find(object_id) != object_colors_->end())
2046  return true;
2047  if (parent_)
2048  return parent_->hasObjectColor(object_id);
2049  return false;
2050 }
2052 const std_msgs::ColorRGBA& PlanningScene::getObjectColor(const std::string& object_id) const
2053 {
2054  if (object_colors_)
2055  {
2056  ObjectColorMap::const_iterator it = object_colors_->find(object_id);
2057  if (it != object_colors_->end())
2058  return it->second;
2059  }
2060  if (parent_)
2061  return parent_->getObjectColor(object_id);
2062  static const std_msgs::ColorRGBA EMPTY;
2063  return EMPTY;
2065 
2067 {
2068  kc.clear();
2069  if (parent_)
2070  parent_->getKnownObjectColors(kc);
2071  if (object_colors_)
2072  for (ObjectColorMap::const_iterator it = object_colors_->begin(); it != object_colors_->end(); ++it)
2073  kc[it->first] = it->second;
2075 
2076 void PlanningScene::setObjectColor(const std::string& object_id, const std_msgs::ColorRGBA& color)
2077 {
2078  if (object_id.empty())
2079  {
2080  ROS_ERROR_NAMED(LOGNAME, "Cannot set color of object with empty object_id.");
2081  return;
2082  }
2083  if (!object_colors_)
2084  object_colors_ = std::make_unique<ObjectColorMap>();
2085  (*object_colors_)[object_id] = color;
2086 }
2087 
2088 void PlanningScene::removeObjectColor(const std::string& object_id)
2089 {
2090  if (object_colors_)
2091  object_colors_->erase(object_id);
2092 }
2093 
2094 bool PlanningScene::isStateColliding(const moveit_msgs::RobotState& state, const std::string& group, bool verbose) const
2095 {
2098  return isStateColliding(s, group, verbose);
2099 }
2100 
2101 bool PlanningScene::isStateColliding(const std::string& group, bool verbose)
2102 {
2103  if (getCurrentState().dirtyCollisionBodyTransforms())
2104  return isStateColliding(getCurrentStateNonConst(), group, verbose);
2105  else
2106  return isStateColliding(getCurrentState(), group, verbose);
2107 }
2109 bool PlanningScene::isStateColliding(const moveit::core::RobotState& state, const std::string& group, bool verbose) const
2110 {
2112  req.verbose = verbose;
2113  req.group_name = group;
2115  checkCollision(req, res, state);
2116  return res.collision;
2117 }
2118 
2119 bool PlanningScene::isStateFeasible(const moveit_msgs::RobotState& state, bool verbose) const
2121  if (state_feasibility_)
2122  {
2125  return state_feasibility_(s, verbose);
2126  }
2127  return true;
2128 }
2129 
2130 bool PlanningScene::isStateFeasible(const moveit::core::RobotState& state, bool verbose) const
2131 {
2132  if (state_feasibility_)
2133  return state_feasibility_(state, verbose);
2134  return true;
2135 }
2136 
2137 bool PlanningScene::isStateConstrained(const moveit_msgs::RobotState& state, const moveit_msgs::Constraints& constr,
2138  bool verbose) const
2139 {
2142  return isStateConstrained(s, constr, verbose);
2143 }
2144 
2145 bool PlanningScene::isStateConstrained(const moveit::core::RobotState& state, const moveit_msgs::Constraints& constr,
2146  bool verbose) const
2147 {
2148  kinematic_constraints::KinematicConstraintSetPtr ks(
2150  ks->add(constr, getTransforms());
2151  if (ks->empty())
2152  return true;
2153  else
2154  return isStateConstrained(state, *ks, verbose);
2155 }
2156 
2157 bool PlanningScene::isStateConstrained(const moveit_msgs::RobotState& state,
2158  const kinematic_constraints::KinematicConstraintSet& constr, bool verbose) const
2159 {
2162  return isStateConstrained(s, constr, verbose);
2163 }
2164 
2166  const kinematic_constraints::KinematicConstraintSet& constr, bool verbose) const
2167 {
2168  return constr.decide(state, verbose).satisfied;
2170 
2171 bool PlanningScene::isStateValid(const moveit::core::RobotState& state, const std::string& group, bool verbose) const
2172 {
2173  static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2174  return isStateValid(state, EMP_CONSTRAINTS, group, verbose);
2175 }
2176 
2177 bool PlanningScene::isStateValid(const moveit_msgs::RobotState& state, const std::string& group, bool verbose) const
2178 {
2179  static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2180  return isStateValid(state, EMP_CONSTRAINTS, group, verbose);
2181 }
2182 
2183 bool PlanningScene::isStateValid(const moveit_msgs::RobotState& state, const moveit_msgs::Constraints& constr,
2184  const std::string& group, bool verbose) const
2185 {
2188  return isStateValid(s, constr, group, verbose);
2190 
2191 bool PlanningScene::isStateValid(const moveit::core::RobotState& state, const moveit_msgs::Constraints& constr,
2192  const std::string& group, bool verbose) const
2193 {
2194  if (isStateColliding(state, group, verbose))
2195  return false;
2196  if (!isStateFeasible(state, verbose))
2197  return false;
2198  return isStateConstrained(state, constr, verbose);
2199 }
2200 
2202  const kinematic_constraints::KinematicConstraintSet& constr, const std::string& group,
2203  bool verbose) const
2204 {
2205  if (isStateColliding(state, group, verbose))
2206  return false;
2207  if (!isStateFeasible(state, verbose))
2208  return false;
2209  return isStateConstrained(state, constr, verbose);
2210 }
2211 
2212 bool PlanningScene::isPathValid(const moveit_msgs::RobotState& start_state,
2213  const moveit_msgs::RobotTrajectory& trajectory, const std::string& group, bool verbose,
2214  std::vector<std::size_t>* invalid_index) const
2216  static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2217  static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2218  return isPathValid(start_state, trajectory, EMP_CONSTRAINTS, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2219 }
2220 
2221 bool PlanningScene::isPathValid(const moveit_msgs::RobotState& start_state,
2222  const moveit_msgs::RobotTrajectory& trajectory,
2223  const moveit_msgs::Constraints& path_constraints, const std::string& group,
2224  bool verbose, std::vector<std::size_t>* invalid_index) const
2225 {
2226  static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2227  return isPathValid(start_state, trajectory, path_constraints, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2228 }
2229 
2230 bool PlanningScene::isPathValid(const moveit_msgs::RobotState& start_state,
2231  const moveit_msgs::RobotTrajectory& trajectory,
2232  const moveit_msgs::Constraints& path_constraints,
2233  const moveit_msgs::Constraints& goal_constraints, const std::string& group,
2234  bool verbose, std::vector<std::size_t>* invalid_index) const
2235 {
2236  std::vector<moveit_msgs::Constraints> goal_constraints_vector(1, goal_constraints);
2237  return isPathValid(start_state, trajectory, path_constraints, goal_constraints_vector, group, verbose, invalid_index);
2238 }
2239 
2240 bool PlanningScene::isPathValid(const moveit_msgs::RobotState& start_state,
2241  const moveit_msgs::RobotTrajectory& trajectory,
2242  const moveit_msgs::Constraints& path_constraints,
2243  const std::vector<moveit_msgs::Constraints>& goal_constraints, const std::string& group,
2244  bool verbose, std::vector<std::size_t>* invalid_index) const
2245 {
2249  t.setRobotTrajectoryMsg(start, trajectory);
2250  return isPathValid(t, path_constraints, goal_constraints, group, verbose, invalid_index);
2251 }
2252 
2254  const moveit_msgs::Constraints& path_constraints,
2255  const std::vector<moveit_msgs::Constraints>& goal_constraints, const std::string& group,
2256  bool verbose, std::vector<std::size_t>* invalid_index) const
2257 {
2258  bool result = true;
2259  if (invalid_index)
2260  invalid_index->clear();
2262  ks_p.add(path_constraints, getTransforms());
2263  std::size_t n_wp = trajectory.getWayPointCount();
2264  for (std::size_t i = 0; i < n_wp; ++i)
2265  {
2266  const moveit::core::RobotState& st = trajectory.getWayPoint(i);
2267 
2268  bool this_state_valid = true;
2269  if (isStateColliding(st, group, verbose))
2270  this_state_valid = false;
2271  if (!isStateFeasible(st, verbose))
2272  this_state_valid = false;
2273  if (!ks_p.empty() && !ks_p.decide(st, verbose).satisfied)
2274  this_state_valid = false;
2275 
2276  if (!this_state_valid)
2277  {
2278  if (invalid_index)
2279  invalid_index->push_back(i);
2280  else
2281  return false;
2282  result = false;
2283  }
2284 
2285  // check goal for last state
2286  if (i + 1 == n_wp && !goal_constraints.empty())
2287  {
2288  bool found = false;
2289  for (const moveit_msgs::Constraints& goal_constraint : goal_constraints)
2290  {
2291  if (isStateConstrained(st, goal_constraint))
2292  {
2293  found = true;
2294  break;
2295  }
2296  }
2297  if (!found)
2298  {
2299  if (verbose)
2300  ROS_INFO_NAMED(LOGNAME, "Goal not satisfied");
2301  if (invalid_index)
2302  invalid_index->push_back(i);
2303  result = false;
2304  }
2305  }
2306  }
2307  return result;
2308 }
2309 
2311  const moveit_msgs::Constraints& path_constraints,
2312  const moveit_msgs::Constraints& goal_constraints, const std::string& group,
2313  bool verbose, std::vector<std::size_t>* invalid_index) const
2314 {
2315  std::vector<moveit_msgs::Constraints> goal_constraints_vector(1, goal_constraints);
2316  return isPathValid(trajectory, path_constraints, goal_constraints_vector, group, verbose, invalid_index);
2317 }
2318 
2320  const moveit_msgs::Constraints& path_constraints, const std::string& group,
2321  bool verbose, std::vector<std::size_t>* invalid_index) const
2322 {
2323  static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2324  return isPathValid(trajectory, path_constraints, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2325 }
2326 
2327 bool PlanningScene::isPathValid(const robot_trajectory::RobotTrajectory& trajectory, const std::string& group,
2328  bool verbose, std::vector<std::size_t>* invalid_index) const
2329 {
2330  static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2331  static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2332  return isPathValid(trajectory, EMP_CONSTRAINTS, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2333 }
2334 
2335 void PlanningScene::getCostSources(const robot_trajectory::RobotTrajectory& trajectory, std::size_t max_costs,
2336  std::set<collision_detection::CostSource>& costs, double overlap_fraction) const
2337 {
2338  getCostSources(trajectory, max_costs, std::string(), costs, overlap_fraction);
2339 }
2340 
2341 void PlanningScene::getCostSources(const robot_trajectory::RobotTrajectory& trajectory, std::size_t max_costs,
2342  const std::string& group_name, std::set<collision_detection::CostSource>& costs,
2343  double overlap_fraction) const
2344 {
2346  creq.max_cost_sources = max_costs;
2347  creq.group_name = group_name;
2348  creq.cost = true;
2349  std::set<collision_detection::CostSource> cs;
2350  std::set<collision_detection::CostSource> cs_start;
2351  std::size_t n_wp = trajectory.getWayPointCount();
2352  for (std::size_t i = 0; i < n_wp; ++i)
2353  {
2355  checkCollision(creq, cres, trajectory.getWayPoint(i));
2356  cs.insert(cres.cost_sources.begin(), cres.cost_sources.end());
2357  if (i == 0)
2358  cs_start.swap(cres.cost_sources);
2359  }
2360 
2361  if (cs.size() <= max_costs)
2362  costs.swap(cs);
2363  else
2364  {
2365  costs.clear();
2366  std::size_t i = 0;
2367  for (std::set<collision_detection::CostSource>::iterator it = cs.begin(); i < max_costs; ++it, ++i)
2368  costs.insert(*it);
2369  }
2370 
2371  collision_detection::removeCostSources(costs, cs_start, overlap_fraction);
2372  collision_detection::removeOverlapping(costs, overlap_fraction);
2374 
2375 void PlanningScene::getCostSources(const moveit::core::RobotState& state, std::size_t max_costs,
2376  std::set<collision_detection::CostSource>& costs) const
2377 {
2378  getCostSources(state, max_costs, std::string(), costs);
2379 }
2380 
2381 void PlanningScene::getCostSources(const moveit::core::RobotState& state, std::size_t max_costs,
2382  const std::string& group_name,
2383  std::set<collision_detection::CostSource>& costs) const
2384 {
2386  creq.max_cost_sources = max_costs;
2387  creq.group_name = group_name;
2388  creq.cost = true;
2390  checkCollision(creq, cres, state);
2391  cres.cost_sources.swap(costs);
2392 }
2393 
2394 void PlanningScene::printKnownObjects(std::ostream& out) const
2395 {
2396  const std::vector<std::string>& objects = getWorld()->getObjectIds();
2397  std::vector<const moveit::core::AttachedBody*> attached_bodies;
2398  getCurrentState().getAttachedBodies(attached_bodies);
2399 
2400  // Output
2401  out << "-----------------------------------------\n";
2402  out << "PlanningScene Known Objects:\n";
2403  out << " - Collision World Objects:\n ";
2404  for (const std::string& object : objects)
2405  {
2406  out << "\t- " << object << "\n";
2407  }
2408 
2409  out << " - Attached Bodies:\n";
2410  for (const moveit::core::AttachedBody* attached_body : attached_bodies)
2411  {
2412  out << "\t- " << attached_body->getName() << "\n";
2413  }
2414  out << "-----------------------------------------\n";
2415 }
2416 
2417 } // end of namespace planning_scene
planning_scene::PlanningScene::getAllowedCollisionMatrixNonConst
collision_detection::AllowedCollisionMatrix & getAllowedCollisionMatrixNonConst()
Get the allowed collision matrix.
Definition: planning_scene.cpp:644
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:2426
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:898
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:2074
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:841
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:1513
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:799
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:2169
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:2037
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:2367
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:1193
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:1238
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:1200
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:2084
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:621
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:1480
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:610
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:804
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:913
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:2209
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:557
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:869
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:2010
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:2027
planning_scene::PlanningScene::getKnownObjectColors
void getKnownObjectColors(ObjectColorMap &kc) const
Definition: planning_scene.cpp:2098
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:2133
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:1398
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:495
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:533
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:2058
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:2051
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:1444
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:2244
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:1768
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:2064
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:672
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:1176
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:1457
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:1917
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:628
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:2120
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:1042
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:580
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:800
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:1298
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:1390
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:1352
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:2151
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:853
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:605
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:511
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:1381
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:1979
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:877
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:635
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:658
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:1000
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:1895
planning_scene::PlanningScene::processCollisionObjectMsg
bool processCollisionObjectMsg(const moveit_msgs::CollisionObject &object)
Definition: planning_scene.cpp:1727
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:1851
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:1752
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:2108
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 Thu Jan 9 2025 03:24:10