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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Oct 18 2020 13:16:33