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