planning_scene_monitor.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 
41 #include <moveit_msgs/GetPlanningScene.h>
42 
43 #include <dynamic_reconfigure/server.h>
44 #include <moveit_ros_planning/PlanningSceneMonitorDynamicReconfigureConfig.h>
45 #include <tf2/exceptions.h>
47 #include <tf2_eigen/tf2_eigen.h>
50 
51 #include <boost/algorithm/string/join.hpp>
52 
53 #include <memory>
54 
55 namespace planning_scene_monitor
56 {
57 using namespace moveit_ros_planning;
58 
59 static const std::string LOGNAME = "planning_scene_monitor";
60 
61 class PlanningSceneMonitor::DynamicReconfigureImpl
62 {
63 public:
64  DynamicReconfigureImpl(PlanningSceneMonitor* owner)
65  : owner_(owner), dynamic_reconfigure_server_(ros::NodeHandle(decideNamespace(owner->getName())))
66  {
67  dynamic_reconfigure_server_.setCallback(
68  [this](const auto& config, uint32_t level) { dynamicReconfigureCallback(config, level); });
69  }
70 
71 private:
72  // make sure we do not advertise the same service multiple times, in case we use multiple PlanningSceneMonitor
73  // instances in a process
74  static std::string decideNamespace(const std::string& name)
75  {
76  std::string ns = "~/" + name;
77  std::replace(ns.begin(), ns.end(), ' ', '_');
78  std::transform(ns.begin(), ns.end(), ns.begin(), ::tolower);
79  if (ros::service::exists(ns + "/set_parameters", false))
80  {
81  unsigned int c = 1;
82  while (ros::service::exists(ns + boost::lexical_cast<std::string>(c) + "/set_parameters", false))
83  c++;
84  ns += boost::lexical_cast<std::string>(c);
85  }
86  return ns;
87  }
88 
89  void dynamicReconfigureCallback(const PlanningSceneMonitorDynamicReconfigureConfig& config, uint32_t /*level*/)
90  {
92  if (config.publish_geometry_updates)
94  if (config.publish_state_updates)
96  if (config.publish_transforms_updates)
98  if (config.publish_planning_scene)
99  {
100  owner_->setPlanningScenePublishingFrequency(config.publish_planning_scene_hz);
101  owner_->startPublishingPlanningScene(event);
102  }
103  else
104  owner_->stopPublishingPlanningScene();
105  }
106 
107  PlanningSceneMonitor* owner_;
108  dynamic_reconfigure::Server<PlanningSceneMonitorDynamicReconfigureConfig> dynamic_reconfigure_server_;
109 };
110 
111 const std::string PlanningSceneMonitor::DEFAULT_JOINT_STATES_TOPIC = "joint_states";
112 const std::string PlanningSceneMonitor::DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC = "attached_collision_object";
113 const std::string PlanningSceneMonitor::DEFAULT_COLLISION_OBJECT_TOPIC = "collision_object";
114 const std::string PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_WORLD_TOPIC = "planning_scene_world";
115 const std::string PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_TOPIC = "planning_scene";
116 const std::string PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_SERVICE = "get_planning_scene";
117 const std::string PlanningSceneMonitor::MONITORED_PLANNING_SCENE_TOPIC = "monitored_planning_scene";
118 
119 PlanningSceneMonitor::PlanningSceneMonitor(const std::string& robot_description,
120  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, const std::string& name)
121  : PlanningSceneMonitor(planning_scene::PlanningScenePtr(), robot_description, tf_buffer, name)
122 {
123 }
124 
125 PlanningSceneMonitor::PlanningSceneMonitor(const planning_scene::PlanningScenePtr& scene,
126  const std::string& robot_description,
127  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, const std::string& name)
128  : PlanningSceneMonitor(scene, std::make_shared<robot_model_loader::RobotModelLoader>(robot_description), tf_buffer,
129  name)
130 {
131 }
132 
133 PlanningSceneMonitor::PlanningSceneMonitor(const robot_model_loader::RobotModelLoaderPtr& rm_loader,
134  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, const std::string& name)
135  : PlanningSceneMonitor(planning_scene::PlanningScenePtr(), rm_loader, tf_buffer, name)
136 {
137 }
138 
139 PlanningSceneMonitor::PlanningSceneMonitor(const planning_scene::PlanningScenePtr& scene,
140  const robot_model_loader::RobotModelLoaderPtr& rm_loader,
141  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, const std::string& name)
142  : monitor_name_(name), nh_("~"), tf_buffer_(tf_buffer), rm_loader_(rm_loader)
143 {
146  spinner_ = std::make_shared<ros::AsyncSpinner>(1, &queue_);
147  spinner_->start();
148  initialize(scene);
149 }
150 
151 PlanningSceneMonitor::PlanningSceneMonitor(const planning_scene::PlanningScenePtr& scene,
152  const robot_model_loader::RobotModelLoaderPtr& rm_loader,
153  const ros::NodeHandle& nh, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
154  const std::string& name)
155  : monitor_name_(name), nh_("~"), root_nh_(nh), tf_buffer_(tf_buffer), rm_loader_(rm_loader)
156 {
157  // use same callback queue as root_nh_
159  initialize(scene);
160 }
161 
163 {
164  if (scene_)
165  {
166  scene_->setCollisionObjectUpdateCallback(collision_detection::World::ObserverCallbackFn());
167  scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback());
168  }
173 
174  spinner_.reset();
175  delete reconfigure_impl_;
176  current_state_monitor_.reset();
177  scene_const_.reset();
178  scene_.reset();
179  parent_scene_.reset();
180  robot_model_.reset();
181  rm_loader_.reset();
182 }
183 
184 planning_scene::PlanningScenePtr PlanningSceneMonitor::copyPlanningScene(const moveit_msgs::PlanningScene& diff)
185 {
186  // We cannot use LockedPlanningSceneRO for RAII because it requires a PSMPtr
187  // Instead assume clone will not throw
188  lockSceneRead();
190  unlockSceneRead();
191 
192  if (!moveit::core::isEmpty(diff))
193  scene->setPlanningSceneDiffMsg(diff);
194  return scene;
195 }
196 
197 void PlanningSceneMonitor::initialize(const planning_scene::PlanningScenePtr& scene)
198 {
200  moveit::tools::Profiler::ScopedBlock prof_block("PlanningSceneMonitor::initialize");
201 
202  if (monitor_name_.empty())
203  monitor_name_ = "planning_scene_monitor";
204  robot_description_ = rm_loader_->getRobotDescription();
205  if (rm_loader_->getModel())
206  {
207  robot_model_ = rm_loader_->getModel();
208  scene_ = scene;
209  if (!scene_)
210  {
211  try
212  {
213  scene_ = std::make_shared<planning_scene::PlanningScene>(rm_loader_->getModel());
216 
217  scene_->getCollisionEnvNonConst()->setPadding(default_robot_padd_);
218  scene_->getCollisionEnvNonConst()->setScale(default_robot_scale_);
219  for (const std::pair<const std::string, double>& it : default_robot_link_padd_)
220  {
221  scene_->getCollisionEnvNonConst()->setLinkPadding(it.first, it.second);
222  }
223  for (const std::pair<const std::string, double>& it : default_robot_link_scale_)
224  {
225  scene_->getCollisionEnvNonConst()->setLinkScale(it.first, it.second);
226  }
227  scene_->propogateRobotPadding();
228  }
230  {
231  ROS_ERROR_NAMED(LOGNAME, "Configuration of planning scene failed");
232  scene_.reset();
233  }
234  }
235  // scene_const_ is set regardless if scene_ is null or not
237  if (scene_)
238  {
239  // The scene_ is loaded on the collision loader only if it was correctly instantiated
241  scene_->setAttachedBodyUpdateCallback([this](moveit::core::AttachedBody* body, bool attached) {
243  });
244  scene_->setCollisionObjectUpdateCallback(
245  [this](const collision_detection::World::ObjectConstPtr& object, collision_detection::World::Action action) {
246  currentWorldObjectUpdateCallback(object, action);
247  });
248  }
249  }
250  else
251  {
252  ROS_ERROR_NAMED(LOGNAME, "Robot model not loaded");
253  }
254 
257 
261 
262  double temp_wait_time = 0.05;
263 
264  if (!robot_description_.empty())
265  nh_.param(robot_description_ + "_planning/shape_transform_cache_lookup_wait_time", temp_wait_time, temp_wait_time);
266 
268 
269  state_update_pending_.store(false);
271  false, // not a oneshot timer
272  false); // do not start the timer yet
273 
274  reconfigure_impl_ = new DynamicReconfigureImpl(this);
275 
276  std::vector<std::string> ignored_frames_vector;
277  nh_.param("planning_scene_monitor_options/ignored_frames", ignored_frames_vector, std::vector<std::string>());
278  ignored_frames_ = std::set<std::string>(ignored_frames_vector.begin(), ignored_frames_vector.end());
279 }
280 
282 {
283  if (scene_)
284  {
285  if (flag)
286  {
287  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
288  if (scene_)
289  {
290  scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback());
291  scene_->setCollisionObjectUpdateCallback(collision_detection::World::ObserverCallbackFn());
292  scene_->decoupleParent();
294  scene_ = parent_scene_->diff();
296  scene_->setAttachedBodyUpdateCallback([this](moveit::core::AttachedBody* body, bool attached) {
298  });
299  scene_->setCollisionObjectUpdateCallback(
300  [this](const collision_detection::World::ObjectConstPtr& object,
302  }
303  }
304  else
305  {
307  {
308  ROS_WARN_NAMED(LOGNAME, "Diff monitoring was stopped while publishing planning scene diffs. "
309  "Stopping planning scene diff publisher");
311  }
312  {
313  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
314  if (scene_)
315  {
316  scene_->decoupleParent();
317  parent_scene_.reset();
318  // remove the '+' added by .diff() at the end of the scene name
319  if (!scene_->getName().empty())
320  {
321  if (scene_->getName()[scene_->getName().length() - 1] == '+')
322  scene_->setName(scene_->getName().substr(0, scene_->getName().length() - 1));
323  }
324  }
325  }
326  }
327  }
328 }
329 
331 {
333  {
334  std::unique_ptr<boost::thread> copy;
335  copy.swap(publish_planning_scene_);
336  new_scene_update_condition_.notify_all();
337  copy->join();
338  monitorDiffs(false);
340  ROS_INFO_NAMED(LOGNAME, "Stopped publishing maintained planning scene.");
341  }
342 }
343 
344 void PlanningSceneMonitor::startPublishingPlanningScene(SceneUpdateType update_type,
345  const std::string& planning_scene_topic)
346 {
347  publish_update_types_ = update_type;
349  {
350  planning_scene_publisher_ = nh_.advertise<moveit_msgs::PlanningScene>(planning_scene_topic, 100, false);
351  ROS_INFO_NAMED(LOGNAME, "Publishing maintained planning scene on '%s'", planning_scene_topic.c_str());
352  monitorDiffs(true);
353  publish_planning_scene_ = std::make_unique<boost::thread>([this] { scenePublishingThread(); });
354  }
355 }
356 
358 {
359  ROS_DEBUG_NAMED(LOGNAME, "Started scene publishing thread ...");
360 
361  // publish the full planning scene once
362  {
363  moveit_msgs::PlanningScene msg;
364  {
366  if (octomap_monitor_)
367  lock = octomap_monitor_->getOcTreePtr()->reading();
368  scene_->getPlanningSceneMsg(msg);
369  }
371  ROS_DEBUG_NAMED(LOGNAME, "Published the full planning scene: '%s'", msg.name.c_str());
372  }
373 
374  do
375  {
376  moveit_msgs::PlanningScene msg;
377  bool publish_msg = false;
378  bool is_full = false;
380  {
381  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
383  new_scene_update_condition_.wait(ulock);
385  {
387  {
389  is_full = true;
390  else
391  {
393  if (octomap_monitor_)
394  lock = octomap_monitor_->getOcTreePtr()->reading();
395  scene_->getPlanningSceneDiffMsg(msg);
397  {
398  msg.robot_state.attached_collision_objects.clear();
399  msg.robot_state.is_diff = true;
400  }
401  }
402  boost::recursive_mutex::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); // we don't want the
403  // transform cache to
404  // update while we are
405  // potentially changing
406  // attached bodies
407  scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback());
408  scene_->setCollisionObjectUpdateCallback(collision_detection::World::ObserverCallbackFn());
409  scene_->pushDiffs(parent_scene_);
410  scene_->clearDiffs();
411  scene_->setAttachedBodyUpdateCallback([this](moveit::core::AttachedBody* body, bool attached) {
413  });
414  scene_->setCollisionObjectUpdateCallback(
415  [this](const collision_detection::World::ObjectConstPtr& object,
417  if (octomap_monitor_)
418  {
419  excludeAttachedBodiesFromOctree(); // in case updates have happened to the attached bodies, put them in
420  excludeWorldObjectsFromOctree(); // in case updates have happened to the attached bodies, put them in
421  }
422  if (is_full)
423  {
425  if (octomap_monitor_)
426  lock = octomap_monitor_->getOcTreePtr()->reading();
427  scene_->getPlanningSceneMsg(msg);
428  }
429  // also publish timestamp of this robot_state
430  msg.robot_state.joint_state.header.stamp = last_robot_motion_time_;
431  publish_msg = true;
432  }
434  }
435  }
436  if (publish_msg)
437  {
439  if (is_full)
440  ROS_DEBUG_NAMED(LOGNAME, "Published full planning scene: '%s'", msg.name.c_str());
441  rate.sleep();
442  }
443  } while (publish_planning_scene_);
444 }
445 
446 void PlanningSceneMonitor::getMonitoredTopics(std::vector<std::string>& topics) const
447 {
448  topics.clear();
450  {
451  const std::string& t = current_state_monitor_->getMonitoredTopic();
452  if (!t.empty())
453  topics.push_back(t);
454  }
456  topics.push_back(planning_scene_subscriber_.getTopic());
458  topics.push_back(collision_object_subscriber_.getTopic());
460  topics.push_back(planning_scene_world_subscriber_.getTopic());
461 }
462 
463 namespace
464 {
465 bool sceneIsParentOf(const planning_scene::PlanningSceneConstPtr& scene,
466  const planning_scene::PlanningScene* possible_parent)
467 {
468  if (scene && scene.get() == possible_parent)
469  return true;
470  if (scene)
471  return sceneIsParentOf(scene->getParent(), possible_parent);
472  return false;
473 }
474 } // namespace
475 
476 bool PlanningSceneMonitor::updatesScene(const planning_scene::PlanningScenePtr& scene) const
477 {
478  return sceneIsParentOf(scene_const_, scene.get());
479 }
480 
481 bool PlanningSceneMonitor::updatesScene(const planning_scene::PlanningSceneConstPtr& scene) const
482 {
483  return sceneIsParentOf(scene_const_, scene.get());
484 }
485 
486 void PlanningSceneMonitor::triggerSceneUpdateEvent(SceneUpdateType update_type)
487 {
488  // do not modify update functions while we are calling them
489  boost::recursive_mutex::scoped_lock lock(update_lock_);
490 
491  for (boost::function<void(SceneUpdateType)>& update_callback : update_callbacks_)
492  update_callback(update_type);
493  new_scene_update_ = (SceneUpdateType)((int)new_scene_update_ | (int)update_type);
494  new_scene_update_condition_.notify_all();
495 }
496 
497 bool PlanningSceneMonitor::requestPlanningSceneState(const std::string& service_name)
498 {
499  if (get_scene_service_.getService() == service_name)
500  {
501  ROS_FATAL_STREAM_NAMED(LOGNAME, "requestPlanningSceneState() to self-provided service '" << service_name << "'");
502  throw std::runtime_error("requestPlanningSceneState() to self-provided service: " + service_name);
503  }
504  // use global namespace for service
505  ros::ServiceClient client = ros::NodeHandle().serviceClient<moveit_msgs::GetPlanningScene>(service_name);
506  // all scene components are returned if none are specified
507  moveit_msgs::GetPlanningScene srv;
508 
509  // Make sure client is connected to server
510  if (!client.exists())
511  {
512  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Waiting for service `" << service_name << "` to exist.");
514  }
515 
516  if (client.call(srv))
517  {
518  newPlanningSceneMessage(srv.response.scene);
519  }
520  else
521  {
523  LOGNAME, "Failed to call service %s, have you launched move_group or called psm.providePlanningSceneService()?",
524  service_name.c_str());
525  return false;
526  }
527  return true;
528 }
529 
530 void PlanningSceneMonitor::providePlanningSceneService(const std::string& service_name)
531 {
532  // Load the service
535 }
536 
537 bool PlanningSceneMonitor::getPlanningSceneServiceCallback(moveit_msgs::GetPlanningScene::Request& req,
538  moveit_msgs::GetPlanningScene::Response& res)
539 {
540  if (req.components.components & moveit_msgs::PlanningSceneComponents::TRANSFORMS)
542 
543  moveit_msgs::PlanningSceneComponents all_components;
544  all_components.components = UINT_MAX; // Return all scene components if nothing is specified.
545 
546  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
547  scene_->getPlanningSceneMsg(res.scene, req.components.components ? req.components : all_components);
548 
549  return true;
550 }
551 
552 void PlanningSceneMonitor::newPlanningSceneCallback(const moveit_msgs::PlanningSceneConstPtr& scene)
553 {
554  newPlanningSceneMessage(*scene);
555 }
556 
558 {
559  bool removed = false;
560  {
561  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
562  removed = scene_->getWorldNonConst()->removeObject(scene_->OCTOMAP_NS);
563 
564  if (octomap_monitor_)
565  {
566  octomap_monitor_->getOcTreePtr()->lockWrite();
567  octomap_monitor_->getOcTreePtr()->clear();
568  octomap_monitor_->getOcTreePtr()->unlockWrite();
569  }
570  else
571  {
572  ROS_WARN_NAMED(LOGNAME, "Unable to clear octomap since no octomap monitor has been initialized");
573  } // Lift the scoped lock before calling triggerSceneUpdateEvent to avoid deadlock
574  }
575 
576  if (removed)
578 }
579 
580 bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::PlanningScene& scene)
581 {
582  if (!scene_)
583  return false;
584 
585  bool result;
586 
588  std::string old_scene_name;
589  {
590  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
591  // we don't want the transform cache to update while we are potentially changing attached bodies
592  boost::recursive_mutex::scoped_lock prevent_shape_cache_updates(shape_handles_lock_);
593 
595  last_robot_motion_time_ = scene.robot_state.joint_state.header.stamp;
596  ROS_DEBUG_STREAM_NAMED("planning_scene_monitor",
597  "scene update " << fmod(last_update_time_.toSec(), 10.)
598  << " robot stamp: " << fmod(last_robot_motion_time_.toSec(), 10.));
599  old_scene_name = scene_->getName();
600 
601  if (!scene.is_diff && parent_scene_)
602  {
603  // If there is no new robot_state, transfer RobotState from current scene to parent scene
604  if (scene.robot_state.is_diff)
605  parent_scene_->setCurrentState(scene_->getCurrentState());
606  scene_->clearDiffs();
607  result = parent_scene_->setPlanningSceneMsg(scene);
608  // There were no callbacks for individual object changes, so rebuild the octree masks
611  }
612  else
613  {
614  result = scene_->usePlanningSceneMsg(scene);
615  }
616 
617  if (octomap_monitor_)
618  {
619  if (!scene.is_diff && scene.world.octomap.octomap.data.empty())
620  {
621  octomap_monitor_->getOcTreePtr()->lockWrite();
622  octomap_monitor_->getOcTreePtr()->clear();
623  octomap_monitor_->getOcTreePtr()->unlockWrite();
624  }
625  }
626  robot_model_ = scene_->getRobotModel();
627 
628  if (octomap_monitor_)
629  {
630  excludeAttachedBodiesFromOctree(); // in case updates have happened to the attached bodies, put them in
631  excludeWorldObjectsFromOctree(); // in case updates have happened to the attached bodies, put them in
632  }
633  }
634 
635  // if we have a diff, try to more accurately determine the update type
636  if (scene.is_diff)
637  {
638  bool no_other_scene_upd = (scene.name.empty() || scene.name == old_scene_name) &&
639  scene.allowed_collision_matrix.entry_names.empty() && scene.link_padding.empty() &&
640  scene.link_scale.empty();
641  if (no_other_scene_upd)
642  {
643  upd = UPDATE_NONE;
644  if (!moveit::core::isEmpty(scene.world))
645  upd = (SceneUpdateType)((int)upd | (int)UPDATE_GEOMETRY);
646 
647  if (!scene.fixed_frame_transforms.empty())
648  upd = (SceneUpdateType)((int)upd | (int)UPDATE_TRANSFORMS);
649 
650  if (!moveit::core::isEmpty(scene.robot_state))
651  {
652  upd = (SceneUpdateType)((int)upd | (int)UPDATE_STATE);
653  if (!scene.robot_state.attached_collision_objects.empty() || !static_cast<bool>(scene.robot_state.is_diff))
654  upd = (SceneUpdateType)((int)upd | (int)UPDATE_GEOMETRY);
655  }
656  }
657  }
659  return result;
660 }
661 
662 void PlanningSceneMonitor::newPlanningSceneWorldCallback(const moveit_msgs::PlanningSceneWorldConstPtr& world)
663 {
664  if (scene_)
665  {
667  {
668  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
670  scene_->getWorldNonConst()->clearObjects();
671  scene_->processPlanningSceneWorldMsg(*world);
672  if (octomap_monitor_)
673  {
674  if (world->octomap.octomap.data.empty())
675  {
676  octomap_monitor_->getOcTreePtr()->lockWrite();
677  octomap_monitor_->getOcTreePtr()->clear();
678  octomap_monitor_->getOcTreePtr()->unlockWrite();
679  }
680  }
681  }
683  }
684 }
685 
686 void PlanningSceneMonitor::collisionObjectCallback(const moveit_msgs::CollisionObjectConstPtr& obj)
687 {
688  if (!scene_)
689  return;
690 
692  {
693  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
695  if (!scene_->processCollisionObjectMsg(*obj))
696  return;
697  }
699 }
700 
701 void PlanningSceneMonitor::attachObjectCallback(const moveit_msgs::AttachedCollisionObjectConstPtr& obj)
702 {
703  if (scene_)
704  {
706  {
707  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
709  scene_->processAttachedCollisionObjectMsg(*obj);
710  }
712  }
713 }
714 
716 {
717  if (!octomap_monitor_)
718  return;
719 
720  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
721 
723  const std::vector<const moveit::core::LinkModel*>& links = getRobotModel()->getLinkModelsWithCollisionGeometry();
725  bool warned = false;
726  for (const moveit::core::LinkModel* link : links)
727  {
728  std::vector<shapes::ShapeConstPtr> shapes = link->getShapes(); // copy shared ptrs on purpuse
729  for (std::size_t j = 0; j < shapes.size(); ++j)
730  {
731  // merge mesh vertices up to 0.1 mm apart
732  if (shapes[j]->type == shapes::MESH)
733  {
734  shapes::Mesh* m = static_cast<shapes::Mesh*>(shapes[j]->clone());
735  m->mergeVertices(1e-4);
736  shapes[j].reset(m);
737  }
738 
740  if (h)
741  link_shape_handles_[link].push_back(std::make_pair(h, j));
742  }
743  if (!warned && ((ros::WallTime::now() - start) > ros::WallDuration(30.0)))
744  {
745  ROS_WARN_STREAM_NAMED(LOGNAME, "It is likely there are too many vertices in collision geometry");
746  warned = true;
747  }
748  }
749 }
750 
752 {
753  if (!octomap_monitor_)
754  return;
755 
756  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
757 
758  for (std::pair<const moveit::core::LinkModel* const,
759  std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>& link_shape_handle :
761  for (std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>& it : link_shape_handle.second)
762  octomap_monitor_->forgetShape(it.first);
763  link_shape_handles_.clear();
764 }
765 
767 {
768  if (!octomap_monitor_)
769  return;
770 
771  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
772 
773  // clear information about any attached body, without refering to the AttachedBody* ptr (could be invalid)
774  for (std::pair<const moveit::core::AttachedBody* const,
775  std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>& attached_body_shape_handle :
777  for (std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>& it : attached_body_shape_handle.second)
778  octomap_monitor_->forgetShape(it.first);
780 }
781 
783 {
784  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
785 
787  // add attached objects again
788  std::vector<const moveit::core::AttachedBody*> ab;
789  scene_->getCurrentState().getAttachedBodies(ab);
790  for (const moveit::core::AttachedBody* body : ab)
792 }
793 
795 {
796  if (!octomap_monitor_)
797  return;
798 
799  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
800 
801  // clear information about any attached object
802  for (std::pair<const std::string, std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>>>&
803  collision_body_shape_handle : collision_body_shape_handles_)
804  for (std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>& it :
805  collision_body_shape_handle.second)
806  octomap_monitor_->forgetShape(it.first);
808 }
809 
811 {
812  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
813 
815  for (const std::pair<const std::string, collision_detection::World::ObjectPtr>& it : *scene_->getWorld())
816  excludeWorldObjectFromOctree(it.second);
817 }
818 
820 {
821  if (!octomap_monitor_)
822  return;
823 
824  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
825  bool found = false;
826  for (std::size_t i = 0; i < attached_body->getShapes().size(); ++i)
827  {
828  if (attached_body->getShapes()[i]->type == shapes::PLANE || attached_body->getShapes()[i]->type == shapes::OCTREE)
829  continue;
830  occupancy_map_monitor::ShapeHandle h = octomap_monitor_->excludeShape(attached_body->getShapes()[i]);
831  if (h)
832  {
833  found = true;
834  attached_body_shape_handles_[attached_body].push_back(std::make_pair(h, i));
835  }
836  }
837  if (found)
838  ROS_DEBUG_NAMED(LOGNAME, "Excluding attached body '%s' from monitored octomap", attached_body->getName().c_str());
839 }
840 
842 {
843  if (!octomap_monitor_)
844  return;
845 
846  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
847 
848  AttachedBodyShapeHandles::iterator it = attached_body_shape_handles_.find(attached_body);
849  if (it != attached_body_shape_handles_.end())
850  {
851  for (std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>& shape_handle : it->second)
852  octomap_monitor_->forgetShape(shape_handle.first);
853  ROS_DEBUG_NAMED(LOGNAME, "Including attached body '%s' in monitored octomap", attached_body->getName().c_str());
855  }
856 }
857 
858 void PlanningSceneMonitor::excludeWorldObjectFromOctree(const collision_detection::World::ObjectConstPtr& obj)
859 {
860  if (!octomap_monitor_)
861  return;
862 
863  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
864 
865  bool found = false;
866  for (std::size_t i = 0; i < obj->shapes_.size(); ++i)
867  {
868  if (obj->shapes_[i]->type == shapes::PLANE || obj->shapes_[i]->type == shapes::OCTREE)
869  continue;
870  occupancy_map_monitor::ShapeHandle h = octomap_monitor_->excludeShape(obj->shapes_[i]);
871  if (h)
872  {
873  collision_body_shape_handles_[obj->id_].push_back(std::make_pair(h, &obj->global_shape_poses_[i]));
874  found = true;
875  }
876  }
877  if (found)
878  ROS_DEBUG_NAMED(LOGNAME, "Excluding collision object '%s' from monitored octomap", obj->id_.c_str());
879 }
880 
881 void PlanningSceneMonitor::includeWorldObjectInOctree(const collision_detection::World::ObjectConstPtr& obj)
882 {
883  if (!octomap_monitor_)
884  return;
885 
886  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
887 
888  CollisionBodyShapeHandles::iterator it = collision_body_shape_handles_.find(obj->id_);
889  if (it != collision_body_shape_handles_.end())
890  {
891  for (std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>& shape_handle : it->second)
892  octomap_monitor_->forgetShape(shape_handle.first);
893  ROS_DEBUG_NAMED(LOGNAME, "Including collision object '%s' in monitored octomap", obj->id_.c_str());
895  }
896 }
897 
899  bool just_attached)
900 {
901  if (!octomap_monitor_)
902  return;
903 
904  if (just_attached)
905  excludeAttachedBodyFromOctree(attached_body);
906  else
907  includeAttachedBodyInOctree(attached_body);
908 }
909 
910 void PlanningSceneMonitor::currentWorldObjectUpdateCallback(const collision_detection::World::ObjectConstPtr& obj,
912 {
914  return;
916  return;
917 
920  else if (action & collision_detection::World::DESTROY)
922  else
923  {
926  }
927 }
928 
929 bool PlanningSceneMonitor::waitForCurrentRobotState(const ros::Time& t, double wait_time)
930 {
931  if (t.isZero())
932  return false;
934  ros::WallDuration timeout(wait_time);
935 
936  ROS_DEBUG_NAMED(LOGNAME, "sync robot state to: %.3fs", fmod(t.toSec(), 10.));
937 
939  {
940  // Wait for next robot update in state monitor.
941  bool success = current_state_monitor_->waitForCurrentState(t, wait_time);
942 
943  /* As robot updates are passed to the planning scene only in throttled fashion, there might
944  be still an update pending. If so, explicitly update the planning scene here.
945  If waitForCurrentState failed, we didn't get any new state updates within wait_time. */
946  if (success)
947  {
948  if (state_update_pending_.load()) // perform state update
950  return true;
951  }
952 
953  ROS_WARN_NAMED(LOGNAME, "Failed to fetch current robot state.");
954  return false;
955  }
956 
957  // Sometimes there is no state monitor. In this case state updates are received as part of scene updates only.
958  // However, scene updates are only published if the robot actually moves. Hence we need a timeout!
959  // As publishing planning scene updates is throttled (2Hz by default), a 1s timeout is a suitable default.
960  boost::shared_lock<boost::shared_mutex> lock(scene_update_mutex_);
961  ros::Time prev_robot_motion_time = last_robot_motion_time_;
962  while (last_robot_motion_time_ < t && // Wait until the state update actually reaches the scene.
963  timeout > ros::WallDuration())
964  {
965  ROS_DEBUG_STREAM_NAMED(LOGNAME, "last robot motion: " << (t - last_robot_motion_time_).toSec() << " ago");
966  new_scene_update_condition_.wait_for(lock, boost::chrono::nanoseconds(timeout.toNSec()));
967  timeout -= ros::WallTime::now() - start; // compute remaining wait_time
968  }
969  bool success = last_robot_motion_time_ >= t;
970  // suppress warning if we received an update at all
971  if (!success && prev_robot_motion_time != last_robot_motion_time_)
972  ROS_WARN_NAMED(LOGNAME, "Maybe failed to update robot state, time diff: %.3fs",
973  (t - last_robot_motion_time_).toSec());
974 
975  ROS_DEBUG_STREAM_NAMED(LOGNAME, "sync done: robot motion: " << (t - last_robot_motion_time_).toSec()
976  << " scene update: " << (t - last_update_time_).toSec());
977  return success;
978 }
979 
981 {
982  scene_update_mutex_.lock_shared();
983  if (octomap_monitor_)
984  octomap_monitor_->getOcTreePtr()->lockRead();
985 }
986 
988 {
989  if (octomap_monitor_)
990  octomap_monitor_->getOcTreePtr()->unlockRead();
991  scene_update_mutex_.unlock_shared();
992 }
993 
995 {
996  scene_update_mutex_.lock();
997  if (octomap_monitor_)
998  octomap_monitor_->getOcTreePtr()->lockWrite();
999 }
1000 
1002 {
1003  if (octomap_monitor_)
1004  octomap_monitor_->getOcTreePtr()->unlockWrite();
1005  scene_update_mutex_.unlock();
1006 }
1007 
1008 void PlanningSceneMonitor::startSceneMonitor(const std::string& scene_topic)
1009 {
1010  stopSceneMonitor();
1011 
1012  ROS_INFO_NAMED(LOGNAME, "Starting planning scene monitor");
1013  // listen for planning scene updates; these messages include transforms, so no need for filters
1014  if (!scene_topic.empty())
1015  {
1018  ROS_INFO_NAMED(LOGNAME, "Listening to '%s'", root_nh_.resolveName(scene_topic).c_str());
1019  }
1020 }
1021 
1023 {
1025  {
1026  ROS_INFO_NAMED(LOGNAME, "Stopping planning scene monitor");
1028  }
1029 }
1030 
1031 bool PlanningSceneMonitor::getShapeTransformCache(const std::string& target_frame, const ros::Time& target_time,
1034  if (!tf_buffer_)
1035  return false;
1036  try
1037  {
1038  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
1039 
1040  for (const std::pair<const moveit::core::LinkModel* const,
1041  std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>& link_shape_handle :
1043  {
1044  tf_buffer_->canTransform(target_frame, link_shape_handle.first->getName(), target_time,
1046  Eigen::Isometry3d ttr = tf2::transformToEigen(
1047  tf_buffer_->lookupTransform(target_frame, link_shape_handle.first->getName(), target_time));
1048  for (std::size_t j = 0; j < link_shape_handle.second.size(); ++j)
1049  cache[link_shape_handle.second[j].first] =
1050  ttr * link_shape_handle.first->getCollisionOriginTransforms()[link_shape_handle.second[j].second];
1051  }
1052  for (const std::pair<const moveit::core::AttachedBody* const,
1053  std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>&
1054  attached_body_shape_handle : attached_body_shape_handles_)
1055  {
1056  tf_buffer_->canTransform(target_frame, attached_body_shape_handle.first->getAttachedLinkName(), target_time,
1058  Eigen::Isometry3d transform = tf2::transformToEigen(tf_buffer_->lookupTransform(
1059  target_frame, attached_body_shape_handle.first->getAttachedLinkName(), target_time));
1060  for (std::size_t k = 0; k < attached_body_shape_handle.second.size(); ++k)
1061  cache[attached_body_shape_handle.second[k].first] =
1062  transform *
1063  attached_body_shape_handle.first->getShapePosesInLinkFrame()[attached_body_shape_handle.second[k].second];
1064  }
1065  {
1066  tf_buffer_->canTransform(target_frame, scene_->getPlanningFrame(), target_time,
1068  Eigen::Isometry3d transform =
1069  tf2::transformToEigen(tf_buffer_->lookupTransform(target_frame, scene_->getPlanningFrame(), target_time));
1070  for (const std::pair<const std::string,
1071  std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>>>&
1072  collision_body_shape_handle : collision_body_shape_handles_)
1073  for (const std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>& it :
1074  collision_body_shape_handle.second)
1075  cache[it.first] = transform * (*it.second);
1076  }
1077  }
1078  catch (tf2::TransformException& ex)
1079  {
1080  ROS_ERROR_THROTTLE_NAMED(1, LOGNAME, "Transform error: %s", ex.what());
1081  return false;
1082  }
1083  return true;
1084 }
1085 
1086 void PlanningSceneMonitor::startWorldGeometryMonitor(const std::string& collision_objects_topic,
1087  const std::string& planning_scene_world_topic,
1088  const bool load_octomap_monitor)
1089 {
1091  ROS_INFO_NAMED(LOGNAME, "Starting world geometry update monitor for collision objects, attached objects, octomap "
1092  "updates.");
1093 
1094  // Listen to the /collision_objects topic to detect requests to add/remove/update collision objects to/from the world
1095  if (!collision_objects_topic.empty())
1096  {
1098  root_nh_.subscribe(collision_objects_topic, 1024, &PlanningSceneMonitor::collisionObjectCallback, this);
1099  ROS_INFO_NAMED(LOGNAME, "Listening to '%s'", root_nh_.resolveName(collision_objects_topic).c_str());
1100  }
1101 
1102  if (!planning_scene_world_topic.empty())
1103  {
1105  root_nh_.subscribe(planning_scene_world_topic, 1, &PlanningSceneMonitor::newPlanningSceneWorldCallback, this);
1106  ROS_INFO_NAMED(LOGNAME, "Listening to '%s' for planning scene world geometry",
1107  root_nh_.resolveName(planning_scene_world_topic).c_str());
1108  }
1109 
1110  // Ocotomap monitor is optional
1111  if (load_octomap_monitor)
1112  {
1113  if (!octomap_monitor_)
1114  {
1116  std::make_unique<occupancy_map_monitor::OccupancyMapMonitor>(tf_buffer_, scene_->getPlanningFrame());
1120 
1121  octomap_monitor_->setTransformCacheCallback(
1122  [this](const std::string& frame, const ros::Time& stamp, occupancy_map_monitor::ShapeTransformCache& cache) {
1123  return getShapeTransformCache(frame, stamp, cache);
1124  });
1125  octomap_monitor_->setUpdateCallback([this] { octomapUpdateCallback(); });
1126  }
1127  octomap_monitor_->startMonitor();
1128  }
1129 }
1130 
1132 {
1134  {
1135  ROS_INFO_NAMED(LOGNAME, "Stopping world geometry monitor");
1137  }
1139  {
1140  ROS_INFO_NAMED(LOGNAME, "Stopping world geometry monitor");
1142  }
1143  if (octomap_monitor_)
1144  octomap_monitor_->stopMonitor();
1145 }
1146 
1147 void PlanningSceneMonitor::startStateMonitor(const std::string& joint_states_topic,
1148  const std::string& attached_objects_topic)
1149 {
1150  stopStateMonitor();
1151  if (scene_)
1152  {
1154  current_state_monitor_ = std::make_shared<CurrentStateMonitor>(getRobotModel(), tf_buffer_, root_nh_);
1155  current_state_monitor_->addUpdateCallback(
1156  [this](const sensor_msgs::JointStateConstPtr& state) { onStateUpdate(state); });
1157  current_state_monitor_->startStateMonitor(joint_states_topic);
1158 
1159  {
1160  boost::mutex::scoped_lock lock(state_update_mutex_);
1161  if (!dt_state_update_.isZero())
1163  }
1164 
1165  if (!attached_objects_topic.empty())
1166  {
1167  // using regular message filter as there's no header
1169  root_nh_.subscribe(attached_objects_topic, 1024, &PlanningSceneMonitor::attachObjectCallback, this);
1170  ROS_INFO_NAMED(LOGNAME, "Listening to '%s' for attached collision objects",
1171  root_nh_.resolveName(attached_objects_topic).c_str());
1172  }
1173  }
1174  else
1175  ROS_ERROR_NAMED(LOGNAME, "Cannot monitor robot state because planning scene is not configured");
1176 }
1177 
1181  current_state_monitor_->stopStateMonitor();
1184 
1186  state_update_pending_.store(false);
1187 }
1188 
1189 void PlanningSceneMonitor::onStateUpdate(const sensor_msgs::JointStateConstPtr& /* joint_state */)
1190 {
1191  state_update_pending_.store(true);
1192 
1193  // Read access to last_robot_state_update_wall_time_ and dt_state_update_ is unprotected here
1194  // as reading invalid values is not critical (just postpones the next state update)
1195  // only update every dt_state_update_ seconds
1198 }
1199 
1201 {
1202  // Read access to last_robot_state_update_wall_time_ and dt_state_update_ is unprotected here
1203  // as reading invalid values is not critical (just postpones the next state update)
1206 }
1207 
1209 {
1211  return;
1212 
1214  {
1215  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
1217  octomap_monitor_->getOcTreePtr()->lockRead();
1218  try
1219  {
1220  scene_->processOctomapPtr(octomap_monitor_->getOcTreePtr(), Eigen::Isometry3d::Identity());
1221  octomap_monitor_->getOcTreePtr()->unlockRead();
1222  }
1223  catch (...)
1224  {
1225  octomap_monitor_->getOcTreePtr()->unlockRead(); // unlock and rethrow
1226  throw;
1227  }
1228  }
1230 }
1231 
1233 {
1234  bool update = false;
1235  if (hz > std::numeric_limits<double>::epsilon())
1236  {
1237  boost::mutex::scoped_lock lock(state_update_mutex_);
1238  dt_state_update_.fromSec(1.0 / hz);
1241  }
1242  else
1243  {
1244  // stop must be called with state_update_mutex_ unlocked to avoid deadlock
1246  boost::mutex::scoped_lock lock(state_update_mutex_);
1248  if (state_update_pending_.load())
1249  update = true;
1250  }
1251  ROS_INFO_NAMED(LOGNAME, "Updating internal planning scene state at most every %lf seconds", dt_state_update_.toSec());
1252 
1253  if (update)
1255 }
1256 
1257 void PlanningSceneMonitor::updateSceneWithCurrentState(bool skip_update_if_locked)
1258 {
1260  {
1261  std::vector<std::string> missing;
1262  if (!current_state_monitor_->haveCompleteState(missing) &&
1263  (ros::Time::now() - current_state_monitor_->getMonitorStartTime()).toSec() > 1.0)
1264  {
1265  std::string missing_str = boost::algorithm::join(missing, ", ");
1266  ROS_WARN_THROTTLE_NAMED(1, LOGNAME, "The complete state of the robot is not yet known. Missing %s",
1267  missing_str.c_str());
1268  }
1269 
1270  {
1271  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_, boost::defer_lock);
1272  if (!skip_update_if_locked)
1273  ulock.lock();
1274  else if (!ulock.try_lock())
1275  // Return if we can't lock scene_update_mutex within 100ms, thus not blocking CurrentStateMonitor too long
1276  return;
1277 
1279  ROS_DEBUG_STREAM_NAMED(LOGNAME, "robot state update " << fmod(last_robot_motion_time_.toSec(), 10.));
1280  current_state_monitor_->setToCurrentState(scene_->getCurrentStateNonConst());
1281  scene_->getCurrentStateNonConst().update(); // compute all transforms
1282  }
1283 
1284  // Update state_update_mutex_ and last_robot_state_update_wall_time_
1285  {
1286  boost::mutex::scoped_lock lock(state_update_mutex_);
1288  state_update_pending_.store(false);
1289  }
1290 
1292  }
1293  else
1294  ROS_ERROR_THROTTLE_NAMED(1, LOGNAME, "State monitor is not active. Unable to set the planning scene state");
1295 }
1296 
1297 void PlanningSceneMonitor::addUpdateCallback(const boost::function<void(SceneUpdateType)>& fn)
1298 {
1299  boost::recursive_mutex::scoped_lock lock(update_lock_);
1300  if (fn)
1301  update_callbacks_.push_back(fn);
1302 }
1303 
1305 {
1306  boost::recursive_mutex::scoped_lock lock(update_lock_);
1307  update_callbacks_.clear();
1308 }
1309 
1311 {
1313  ROS_DEBUG_NAMED(LOGNAME, "Maximum frequency for publishing a planning scene is now %lf Hz",
1315 }
1316 
1317 void PlanningSceneMonitor::getUpdatedFrameTransforms(std::vector<geometry_msgs::TransformStamped>& transforms)
1318 {
1319  const std::string& target = getRobotModel()->getModelFrame();
1320 
1321  std::vector<std::string> all_frame_names;
1322  tf_buffer_->_getFrameStrings(all_frame_names);
1323  for (const std::string& all_frame_name : all_frame_names)
1324  {
1325  if (all_frame_name == target || getRobotModel()->hasLinkModel(all_frame_name) || checkFrameIgnored(all_frame_name))
1326  continue;
1327 
1328  geometry_msgs::TransformStamped f;
1329  try
1330  {
1331  f = tf_buffer_->lookupTransform(target, all_frame_name, ros::Time(0));
1332  }
1333  catch (tf2::TransformException& ex)
1334  {
1335  ROS_WARN_STREAM_NAMED(LOGNAME, "Unable to transform object from frame '"
1336  << all_frame_name << "' to planning frame '" << target << "' (" << ex.what()
1337  << ")");
1338  continue;
1339  }
1340  f.header.frame_id = all_frame_name;
1341  f.child_frame_id = target;
1342  transforms.push_back(f);
1343  }
1344 }
1345 
1347 {
1348  if (!tf_buffer_)
1349  return;
1350 
1351  if (scene_)
1352  {
1353  std::vector<geometry_msgs::TransformStamped> transforms;
1354  getUpdatedFrameTransforms(transforms);
1355  {
1356  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
1357  scene_->getTransformsNonConst().setTransforms(transforms);
1359  }
1361  }
1362 }
1363 
1365 {
1366  if (octomap_monitor_)
1367  octomap_monitor_->publishDebugInformation(flag);
1368 }
1369 
1370 void PlanningSceneMonitor::configureCollisionMatrix(const planning_scene::PlanningScenePtr& scene)
1371 {
1372  if (!scene || robot_description_.empty())
1373  return;
1374  collision_detection::AllowedCollisionMatrix& acm = scene->getAllowedCollisionMatrixNonConst();
1375 
1376  // read overriding values from the param server
1377 
1378  // first we do default collision operations
1379  if (!nh_.hasParam(robot_description_ + "_planning/default_collision_operations"))
1380  ROS_DEBUG_NAMED(LOGNAME, "No additional default collision operations specified");
1381  else
1382  {
1383  ROS_DEBUG_NAMED(LOGNAME, "Reading additional default collision operations");
1384 
1385  XmlRpc::XmlRpcValue coll_ops;
1386  nh_.getParam(robot_description_ + "_planning/default_collision_operations", coll_ops);
1387 
1388  if (coll_ops.getType() != XmlRpc::XmlRpcValue::TypeArray)
1389  {
1390  ROS_WARN_NAMED(LOGNAME, "default_collision_operations is not an array");
1391  return;
1392  }
1393 
1394  if (coll_ops.size() == 0)
1395  {
1396  ROS_WARN_NAMED(LOGNAME, "No collision operations in default collision operations");
1397  return;
1398  }
1399 
1400  for (int i = 0; i < coll_ops.size(); ++i) // NOLINT(modernize-loop-convert)
1401  {
1402  if (!coll_ops[i].hasMember("object1") || !coll_ops[i].hasMember("object2") || !coll_ops[i].hasMember("operation"))
1403  {
1404  ROS_WARN_NAMED(LOGNAME, "All collision operations must have two objects and an operation");
1405  continue;
1406  }
1407  acm.setEntry(std::string(coll_ops[i]["object1"]), std::string(coll_ops[i]["object2"]),
1408  std::string(coll_ops[i]["operation"]) == "disable");
1409  }
1410  }
1411 }
1412 
1414 {
1415  if (robot_description_.empty())
1416  {
1417  default_robot_padd_ = 0.0;
1418  default_robot_scale_ = 1.0;
1419  default_object_padd_ = 0.0;
1420  default_attached_padd_ = 0.0;
1421  return;
1422  }
1423 
1424  // print deprecation warning if necessary
1425  // TODO: remove this warning after 06/2022
1426  const std::string old_robot_description =
1427  (robot_description_[0] == '/') ? robot_description_.substr(1) : robot_description_;
1428  if (nh_.resolveName(old_robot_description) != nh_.resolveName(robot_description_))
1429  {
1430  if (nh_.hasParam(old_robot_description + "_planning/default_robot_padding") ||
1431  nh_.hasParam(old_robot_description + "_planning/default_robot_scale") ||
1432  nh_.hasParam(old_robot_description + "_planning/default_object_padding") ||
1433  nh_.hasParam(old_robot_description + "_planning/default_attached_padding") ||
1434  nh_.hasParam(old_robot_description + "_planning/default_robot_link_padding") ||
1435  nh_.hasParam(old_robot_description + "_planning/default_robot_link_scale"))
1436  {
1437  ROS_WARN_STREAM_NAMED(LOGNAME, "The path for the padding parameters has changed!\n"
1438  "Old parameter path: '"
1439  << nh_.resolveName(old_robot_description + "_planning/")
1440  << "'\n"
1441  "New parameter path: '"
1442  << nh_.resolveName(robot_description_ + "_planning/")
1443  << "'\n"
1444  "Ignoring old parameters. Please update your moveit config!");
1445  }
1446  }
1447 
1448  nh_.param(robot_description_ + "_planning/default_robot_padding", default_robot_padd_, 0.0);
1449  nh_.param(robot_description_ + "_planning/default_robot_scale", default_robot_scale_, 1.0);
1450  nh_.param(robot_description_ + "_planning/default_object_padding", default_object_padd_, 0.0);
1451  nh_.param(robot_description_ + "_planning/default_attached_padding", default_attached_padd_, 0.0);
1452  nh_.param(robot_description_ + "_planning/default_robot_link_padding", default_robot_link_padd_,
1453  std::map<std::string, double>());
1454  nh_.param(robot_description_ + "_planning/default_robot_link_scale", default_robot_link_scale_,
1455  std::map<std::string, double>());
1456 
1457  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Loaded " << default_robot_link_padd_.size() << " default link paddings");
1458  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Loaded " << default_robot_link_scale_.size() << " default link scales");
1459 }
1460 
1461 bool PlanningSceneMonitor::checkFrameIgnored(const std::string& frame)
1462 {
1463  return (ignored_frames_.find(frame) != ignored_frames_.end());
1464 }
1465 } // namespace planning_scene_monitor
planning_scene_monitor::PlanningSceneMonitor::excludeWorldObjectFromOctree
void excludeWorldObjectFromOctree(const collision_detection::World::ObjectConstPtr &obj)
Definition: planning_scene_monitor.cpp:890
XmlRpc::XmlRpcValue::size
int size() const
planning_scene_monitor::PlanningSceneMonitor::planning_scene_world_subscriber_
ros::Subscriber planning_scene_world_subscriber_
Definition: planning_scene_monitor.h:541
moveit::core::LinkModel
planning_scene_monitor::PlanningSceneMonitor::collision_body_shape_handles_
CollisionBodyShapeHandles collision_body_shape_handles_
Definition: planning_scene_monitor.h:566
planning_scene_monitor::PlanningSceneMonitor::publishDebugInformation
void publishDebugInformation(bool flag)
Definition: planning_scene_monitor.cpp:1396
planning_scene_monitor
Definition: current_state_monitor.h:47
planning_scene_monitor::PlanningSceneMonitor::onStateUpdate
void onStateUpdate(const sensor_msgs::JointStateConstPtr &joint_state)
Definition: planning_scene_monitor.cpp:1221
planning_scene_monitor::PlanningSceneMonitor::currentWorldObjectUpdateCallback
void currentWorldObjectUpdateCallback(const collision_detection::World::ObjectConstPtr &object, collision_detection::World::Action action)
Callback for a change in the world maintained by the planning scene.
Definition: planning_scene_monitor.cpp:942
planning_scene_monitor::PlanningSceneMonitor::default_attached_padd_
double default_attached_padd_
default attached padding
Definition: planning_scene_monitor.h:525
planning_scene_monitor::PlanningSceneMonitor::default_robot_link_padd_
std::map< std::string, double > default_robot_link_padd_
default robot link padding
Definition: planning_scene_monitor.h:527
ros::ServiceClient::waitForExistence
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
ROS_ERROR_THROTTLE_NAMED
#define ROS_ERROR_THROTTLE_NAMED(period, name,...)
collision_detection::World::DESTROY
DESTROY
ros::service::exists
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
planning_scene_monitor::PlanningSceneMonitor::configureDefaultPadding
void configureDefaultPadding()
Configure the default padding.
Definition: planning_scene_monitor.cpp:1445
shapes
planning_scene_monitor::PlanningSceneMonitor::attached_body_shape_handles_
AttachedBodyShapeHandles attached_body_shape_handles_
Definition: planning_scene_monitor.h:565
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_SERVICE
static const std::string DEFAULT_PLANNING_SCENE_SERVICE
The name of the service used by default for requesting full planning scene state.
Definition: planning_scene_monitor.h:132
occupancy_map_monitor::ShapeTransformCache
std::map< ShapeHandle, Eigen::Isometry3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Isometry3d > > > ShapeTransformCache
DurationBase< WallDuration >::fromSec
WallDuration & fromSec(double t)
planning_scene_monitor::PlanningSceneMonitor::triggerSceneUpdateEvent
void triggerSceneUpdateEvent(SceneUpdateType update_type)
This function is called every time there is a change to the planning scene.
Definition: planning_scene_monitor.cpp:518
planning_scene_monitor::PlanningSceneMonitor::~PlanningSceneMonitor
~PlanningSceneMonitor()
Definition: planning_scene_monitor.cpp:194
planning_scene_monitor::PlanningSceneMonitor::getShapeTransformCache
bool getShapeTransformCache(const std::string &target_frame, const ros::Time &target_time, occupancy_map_monitor::ShapeTransformCache &cache) const
Definition: planning_scene_monitor.cpp:1063
planning_scene_monitor::PlanningSceneMonitor::stopStateMonitor
void stopStateMonitor()
Stop the state monitor.
Definition: planning_scene_monitor.cpp:1210
planning_scene_monitor::PlanningSceneMonitor::updatesScene
bool updatesScene(const planning_scene::PlanningSceneConstPtr &scene) const
Return true if the scene scene can be updated directly or indirectly by this monitor....
Definition: planning_scene_monitor.cpp:513
planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneMessage
bool newPlanningSceneMessage(const moveit_msgs::PlanningScene &scene)
Definition: planning_scene_monitor.cpp:612
planning_scene_monitor::PlanningSceneMonitor::octomapUpdateCallback
void octomapUpdateCallback()
Callback for octomap updates.
Definition: planning_scene_monitor.cpp:1240
planning_scene_monitor::PlanningSceneMonitor::addUpdateCallback
void addUpdateCallback(const boost::function< void(SceneUpdateType)> &fn)
Add a function to be called when an update to the scene is received.
Definition: planning_scene_monitor.cpp:1329
planning_scene_monitor::PlanningSceneMonitor::spinner_
std::shared_ptr< ros::AsyncSpinner > spinner_
Definition: planning_scene_monitor.h:512
ros::ServiceClient::exists
bool exists()
shapes::PLANE
PLANE
planning_scene_monitor::PlanningSceneMonitor::updateSceneWithCurrentState
void updateSceneWithCurrentState(bool skip_update_if_locked=false)
Update the scene using the monitored state. This function is automatically called when an update to t...
Definition: planning_scene_monitor.cpp:1289
tf2_eigen.h
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
ros
planning_scene_monitor::PlanningSceneMonitor::copyPlanningScene
planning_scene::PlanningScenePtr copyPlanningScene(const moveit_msgs::PlanningScene &diff=moveit_msgs::PlanningScene())
Returns a copy of the current planning scene.
Definition: planning_scene_monitor.cpp:216
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
planning_scene_monitor::PlanningSceneMonitor::collision_loader_
collision_detection::CollisionPluginLoader collision_loader_
Definition: planning_scene_monitor.h:621
planning_scene_monitor::PlanningSceneMonitor::scenePublishingThread
void scenePublishingThread()
Definition: planning_scene_monitor.cpp:389
planning_scene_monitor::PlanningSceneMonitor::default_robot_padd_
double default_robot_padd_
default robot padding
Definition: planning_scene_monitor.h:519
robot_model_loader
Definition: robot_model_loader.h:44
planning_scene::PlanningScene
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
planning_scene_monitor::PlanningSceneMonitor::attached_collision_object_subscriber_
ros::Subscriber attached_collision_object_subscriber_
Definition: planning_scene_monitor.h:543
planning_scene_monitor::PlanningSceneMonitor::setStateUpdateFrequency
void setStateUpdateFrequency(double hz)
Update the scene using the monitored state at a specified frequency, in Hz. This function has an effe...
Definition: planning_scene_monitor.cpp:1264
planning_scene_monitor::PlanningSceneMonitor::collisionObjectCallback
void collisionObjectCallback(const moveit_msgs::CollisionObjectConstPtr &obj)
Callback for a new collision object msg.
Definition: planning_scene_monitor.cpp:718
planning_scene_monitor::PlanningSceneMonitor::scene_const_
planning_scene::PlanningSceneConstPtr scene_const_
Definition: planning_scene_monitor.h:503
ros::Subscriber::getTopic
std::string getTopic() const
planning_scene_monitor::PlanningSceneMonitor::update_lock_
boost::recursive_mutex update_lock_
lock access to update_callbacks_
Definition: planning_scene_monitor.h:570
planning_scene_monitor::PlanningSceneMonitor::state_update_pending_
std::atomic< bool > state_update_pending_
True if current_state_monitor_ has a newer RobotState than scene_.
Definition: planning_scene_monitor.h:594
TimeBase< Time, Duration >::toSec
double toSec() const
planning_scene_monitor::PlanningSceneMonitor::collision_object_subscriber_
ros::Subscriber collision_object_subscriber_
Definition: planning_scene_monitor.h:544
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
planning_scene_monitor::PlanningSceneMonitor::getPlanningScene
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
Definition: planning_scene_monitor.h:224
collision_detection::World::Action
ros::Subscriber::shutdown
void shutdown()
moveit::tools::Profiler::ScopedStart
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
shapes::Mesh::mergeVertices
void mergeVertices(double threshold)
shapes::Mesh
planning_scene_monitor::PlanningSceneMonitor::updateFrameTransforms
void updateFrameTransforms()
Update the transforms for the frames that are not part of the kinematic model using tf....
Definition: planning_scene_monitor.cpp:1378
planning_scene_monitor::LOGNAME
static const std::string LOGNAME
Definition: planning_scene_monitor.cpp:91
planning_scene_monitor::PlanningSceneMonitor::excludeWorldObjectsFromOctree
void excludeWorldObjectsFromOctree()
Definition: planning_scene_monitor.cpp:842
planning_scene_monitor::PlanningSceneMonitor::last_robot_motion_time_
ros::Time last_robot_motion_time_
Last time the state was updated.
Definition: planning_scene_monitor.h:507
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
obj
CollisionObject< S > * obj
planning_scene_monitor::PlanningSceneMonitor::rm_loader_
robot_model_loader::RobotModelLoaderPtr rm_loader_
Definition: planning_scene_monitor.h:618
planning_scene_monitor::PlanningSceneMonitor::new_scene_update_
SceneUpdateType new_scene_update_
Definition: planning_scene_monitor.h:536
planning_scene_monitor::PlanningSceneMonitor::tf_buffer_
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
Definition: planning_scene_monitor.h:514
shapes::MESH
MESH
f
f
planning_scene_monitor::PlanningSceneMonitor::state_update_timer_
ros::WallTimer state_update_timer_
timer for state updates.
Definition: planning_scene_monitor.h:616
ros::WallTimer::start
void start()
planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType
SceneUpdateType
Definition: planning_scene_monitor.h:96
moveit::core::AttachedBody
planning_scene_monitor::PlanningSceneMonitor::default_robot_scale_
double default_robot_scale_
default robot scaling
Definition: planning_scene_monitor.h:521
planning_scene_monitor::PlanningSceneMonitor::initialize
void initialize(const planning_scene::PlanningScenePtr &scene)
Initialize the planning scene monitor.
Definition: planning_scene_monitor.cpp:229
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
planning_scene_monitor::PlanningSceneMonitor::publish_update_types_
SceneUpdateType publish_update_types_
Definition: planning_scene_monitor.h:535
collision_detection::AllowedCollisionMatrix::setEntry
void setEntry(bool allowed)
collision_detection::AllowedCollisionMatrix
message_checks.h
planning_scene_monitor::PlanningSceneMonitor::octomap_monitor_
std::unique_ptr< occupancy_map_monitor::OccupancyMapMonitor > octomap_monitor_
Definition: planning_scene_monitor.h:551
moveit::core::isEmpty
bool isEmpty(const geometry_msgs::Pose &msg)
planning_scene_monitor::PlanningSceneMonitor::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Definition: planning_scene_monitor.h:205
planning_scene_monitor::PlanningSceneMonitor::last_update_time_
ros::Time last_update_time_
mutex for stored scene
Definition: planning_scene_monitor.h:506
planning_scene_monitor::PlanningSceneMonitor::new_scene_update_condition_
boost::condition_variable_any new_scene_update_condition_
Definition: planning_scene_monitor.h:537
name
std::string name
ros::Publisher::shutdown
void shutdown()
planning_scene_monitor::PlanningSceneMonitor::lockSceneRead
void lockSceneRead()
Lock the scene for reading (multiple threads can lock for reading at the same time)
Definition: planning_scene_monitor.cpp:1012
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
collision_detection::World::ObserverCallbackFn
boost::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
planning_scene_monitor::PlanningSceneMonitor::unlockSceneRead
void unlockSceneRead()
Unlock the scene from reading (multiple threads can lock for reading at the same time)
Definition: planning_scene_monitor.cpp:1019
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_WORLD_TOPIC
static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC
Definition: planning_scene_monitor.h:126
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
planning_scene_monitor::PlanningSceneMonitor::root_nh_
ros::NodeHandle root_nh_
Definition: planning_scene_monitor.h:510
planning_scene_monitor::PlanningSceneMonitor::current_state_monitor_
CurrentStateMonitorPtr current_state_monitor_
Definition: planning_scene_monitor.h:554
ros::WallTime::now
static WallTime now()
planning_scene_monitor::PlanningSceneMonitor::checkFrameIgnored
bool checkFrameIgnored(const std::string &frame)
Definition: planning_scene_monitor.cpp:1493
planning_scene_monitor::PlanningSceneMonitor::stopPublishingPlanningScene
void stopPublishingPlanningScene()
Stop publishing the maintained planning scene.
Definition: planning_scene_monitor.cpp:362
planning_scene_monitor::PlanningSceneMonitor::excludeAttachedBodyFromOctree
void excludeAttachedBodyFromOctree(const moveit::core::AttachedBody *attached_body)
Definition: planning_scene_monitor.cpp:851
planning_scene_monitor::PlanningSceneMonitor::UPDATE_STATE
@ UPDATE_STATE
The state in the monitored scene was updated.
Definition: planning_scene_monitor.h:102
planning_scene_monitor::PlanningSceneMonitor::reconfigure_impl_
DynamicReconfigureImpl * reconfigure_impl_
Definition: planning_scene_monitor.h:623
planning_scene_monitor::PlanningSceneMonitor::queue_
ros::CallbackQueue queue_
Definition: planning_scene_monitor.h:511
planning_scene_monitor::PlanningSceneMonitor::stopSceneMonitor
void stopSceneMonitor()
Stop the scene monitor.
Definition: planning_scene_monitor.cpp:1054
planning_scene_monitor::PlanningSceneMonitor::stopWorldGeometryMonitor
void stopWorldGeometryMonitor()
Stop the world geometry monitor.
Definition: planning_scene_monitor.cpp:1163
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_COLLISION_OBJECT_TOPIC
static const std::string DEFAULT_COLLISION_OBJECT_TOPIC
The name of the topic used by default for receiving collision objects in the world.
Definition: planning_scene_monitor.h:122
planning_scene_monitor::PlanningSceneMonitor::startStateMonitor
void startStateMonitor(const std::string &joint_states_topic=DEFAULT_JOINT_STATES_TOPIC, const std::string &attached_objects_topic=DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC)
Start the current state monitor.
Definition: planning_scene_monitor.cpp:1179
planning_scene_monitor::PlanningSceneMonitor::excludeRobotLinksFromOctree
void excludeRobotLinksFromOctree()
Definition: planning_scene_monitor.cpp:747
ros::WallTimer::setPeriod
void setPeriod(const WallDuration &period, bool reset=true)
planning_scene_monitor::PlanningSceneMonitor::getPlanningSceneServiceCallback
bool getPlanningSceneServiceCallback(moveit_msgs::GetPlanningScene::Request &req, moveit_msgs::GetPlanningScene::Response &res)
Definition: planning_scene_monitor.cpp:569
planning_scene_monitor::PlanningSceneMonitor::publish_planning_scene_
std::unique_ptr< boost::thread > publish_planning_scene_
Definition: planning_scene_monitor.h:533
ros::ServiceClient
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
planning_scene_monitor.h
planning_scene_monitor::PlanningSceneMonitor::last_robot_state_update_wall_time_
ros::WallTime last_robot_state_update_wall_time_
Last time the state was updated from current_state_monitor_.
Definition: planning_scene_monitor.h:602
planning_scene_monitor::PlanningSceneMonitor::get_scene_service_
ros::ServiceServer get_scene_service_
Definition: planning_scene_monitor.h:548
ros::NodeHandle::getCallbackQueue
CallbackQueueInterface * getCallbackQueue() const
moveit::core::AttachedBodyCallback
boost::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
planning_scene_monitor::PlanningSceneMonitor::unlockSceneWrite
void unlockSceneWrite()
Lock the scene from writing (only one thread can lock for writing and no other thread can lock for re...
Definition: planning_scene_monitor.cpp:1033
planning_scene_monitor::PlanningSceneMonitor::robot_description_
std::string robot_description_
Definition: planning_scene_monitor.h:516
planning_scene_monitor::PlanningSceneMonitor::default_object_padd_
double default_object_padd_
default object padding
Definition: planning_scene_monitor.h:523
planning_scene_monitor::PlanningSceneMonitor::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: planning_scene_monitor.h:619
planning_scene_monitor::PlanningSceneMonitor::includeAttachedBodyInOctree
void includeAttachedBodyInOctree(const moveit::core::AttachedBody *attached_body)
Definition: planning_scene_monitor.cpp:873
planning_scene_monitor::PlanningSceneMonitor::stateUpdateTimerCallback
void stateUpdateTimerCallback(const ros::WallTimerEvent &event)
Definition: planning_scene_monitor.cpp:1232
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::WallTime
planning_scene_monitor::PlanningSceneMonitor::setPlanningScenePublishingFrequency
void setPlanningScenePublishingFrequency(double hz)
Set the maximum frequency at which planning scenes are being published.
Definition: planning_scene_monitor.cpp:1342
planning_scene_monitor::PlanningSceneMonitor::default_robot_link_scale_
std::map< std::string, double > default_robot_link_scale_
default robot link scale
Definition: planning_scene_monitor.h:529
planning_scene_monitor::PlanningSceneMonitor::monitor_name_
std::string monitor_name_
The name of this scene monitor.
Definition: planning_scene_monitor.h:500
collision_detection::OccMapTree::ReadLock
boost::shared_lock< boost::shared_mutex > ReadLock
planning_scene_monitor::PlanningSceneMonitor::publish_planning_scene_frequency_
double publish_planning_scene_frequency_
Definition: planning_scene_monitor.h:534
XmlRpc::XmlRpcValue::getType
const Type & getType() const
ROS_WARN_THROTTLE_NAMED
#define ROS_WARN_THROTTLE_NAMED(period, name,...)
planning_scene_monitor::PlanningSceneMonitor::state_update_mutex_
boost::mutex state_update_mutex_
Definition: planning_scene_monitor.h:597
planning_scene_monitor::PlanningSceneMonitor
PlanningSceneMonitor Subscribes to the topic planning_scene.
Definition: planning_scene_monitor.h:93
tf2::transformToEigen
Eigen::Isometry3d transformToEigen(const geometry_msgs::Transform &t)
ros::NodeHandle::setCallbackQueue
void setCallbackQueue(CallbackQueueInterface *queue)
shapes::OCTREE
OCTREE
planning_scene_monitor::PlanningSceneMonitor::shape_handles_lock_
boost::recursive_mutex shape_handles_lock_
Definition: planning_scene_monitor.h:567
planning_scene_monitor::PlanningSceneMonitor::startWorldGeometryMonitor
void startWorldGeometryMonitor(const std::string &collision_objects_topic=DEFAULT_COLLISION_OBJECT_TOPIC, const std::string &planning_scene_world_topic=DEFAULT_PLANNING_SCENE_WORLD_TOPIC, const bool load_octomap_monitor=true)
Start the OccupancyMapMonitor and listening for:
Definition: planning_scene_monitor.cpp:1118
exceptions.h
ROS_WARN_STREAM_NAMED
#define ROS_WARN_STREAM_NAMED(name, args)
XmlRpc::XmlRpcValue::TypeArray
TypeArray
planning_scene_monitor::PlanningSceneMonitor::UPDATE_NONE
@ UPDATE_NONE
No update.
Definition: planning_scene_monitor.h:99
start
ROSCPP_DECL void start()
occupancy_map_monitor::ShapeHandle
unsigned int ShapeHandle
planning_scene::PlanningScene::clone
static PlanningScenePtr clone(const PlanningSceneConstPtr &scene)
planning_scene_monitor::PlanningSceneMonitor::scene_
planning_scene::PlanningScenePtr scene_
Definition: planning_scene_monitor.h:502
planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneWorldCallback
void newPlanningSceneWorldCallback(const moveit_msgs::PlanningSceneWorldConstPtr &world)
Callback for a new planning scene world.
Definition: planning_scene_monitor.cpp:694
planning_scene_monitor::PlanningSceneMonitor::nh_
ros::NodeHandle nh_
Last time the robot has moved.
Definition: planning_scene_monitor.h:509
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_JOINT_STATES_TOPIC
static const std::string DEFAULT_JOINT_STATES_TOPIC
The name of the topic used by default for receiving joint states.
Definition: planning_scene_monitor.h:116
planning_scene_monitor::PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback
void currentStateAttachedBodyUpdateCallback(moveit::core::AttachedBody *attached_body, bool just_attached)
Callback for a change for an attached object of the current state of the planning scene.
Definition: planning_scene_monitor.cpp:930
ros::WallTimerEvent
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_TOPIC
static const std::string DEFAULT_PLANNING_SCENE_TOPIC
The name of the topic used by default for receiving full planning scenes or planning scene diffs.
Definition: planning_scene_monitor.h:129
planning_scene_monitor::PlanningSceneMonitor::MONITORED_PLANNING_SCENE_TOPIC
static const std::string MONITORED_PLANNING_SCENE_TOPIC
Definition: planning_scene_monitor.h:136
ros::Time
planning_scene_monitor::PlanningSceneMonitor::includeRobotLinksInOctree
void includeRobotLinksInOctree()
Definition: planning_scene_monitor.cpp:783
planning_scene_monitor::PlanningSceneMonitor::waitForCurrentRobotState
bool waitForCurrentRobotState(const ros::Time &t, double wait_time=1.)
Wait for robot state to become more recent than time t.
Definition: planning_scene_monitor.cpp:961
DurationBase< WallDuration >::toNSec
int64_t toNSec() const
planning_scene_monitor::PlanningSceneMonitor::attachObjectCallback
void attachObjectCallback(const moveit_msgs::AttachedCollisionObjectConstPtr &obj)
Callback for a new attached object msg.
Definition: planning_scene_monitor.cpp:733
tf_buffer
tf2_ros::Buffer * tf_buffer
planning_scene_monitor::PlanningSceneMonitor::startSceneMonitor
void startSceneMonitor(const std::string &scene_topic=DEFAULT_PLANNING_SCENE_TOPIC)
Start the scene monitor (ROS topic-based)
Definition: planning_scene_monitor.cpp:1040
std
planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneCallback
void newPlanningSceneCallback(const moveit_msgs::PlanningSceneConstPtr &scene)
Definition: planning_scene_monitor.cpp:584
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
moveit::core::AttachedBody::getShapes
const std::vector< shapes::ShapeConstPtr > & getShapes() const
planning_scene_monitor::PlanningSceneMonitor::planning_scene_subscriber_
ros::Subscriber planning_scene_subscriber_
Definition: planning_scene_monitor.h:540
planning_scene::PlanningScene::OCTOMAP_NS
static const MOVEIT_PLANNING_SCENE_EXPORT std::string OCTOMAP_NS
ros::ServiceServer::getService
std::string getService() const
planning_scene_monitor::PlanningSceneMonitor::includeWorldObjectsInOctree
void includeWorldObjectsInOctree()
Definition: planning_scene_monitor.cpp:826
moveit::tools::Profiler::ScopedBlock
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
planning_scene_monitor::PlanningSceneMonitor::ignored_frames_
std::set< std::string > ignored_frames_
Definition: planning_scene_monitor.h:626
planning_scene_monitor::PlanningSceneMonitor::excludeAttachedBodiesFromOctree
void excludeAttachedBodiesFromOctree()
Definition: planning_scene_monitor.cpp:814
planning_scene_monitor::PlanningSceneMonitor::configureCollisionMatrix
void configureCollisionMatrix(const planning_scene::PlanningScenePtr &scene)
Configure the collision matrix for a particular scene.
Definition: planning_scene_monitor.cpp:1402
planning_scene_monitor::PlanningSceneMonitor::dt_state_update_
ros::WallDuration dt_state_update_
the amount of time to wait in between updates to the robot state
Definition: planning_scene_monitor.h:606
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
planning_scene_monitor::PlanningSceneMonitor::UPDATE_GEOMETRY
@ UPDATE_GEOMETRY
The geometry of the scene was updated. This includes receiving new octomaps, collision objects,...
Definition: planning_scene_monitor.h:109
tf2_geometry_msgs.h
planning_scene_monitor::PlanningSceneMonitor::providePlanningSceneService
void providePlanningSceneService(const std::string &service_name=DEFAULT_PLANNING_SCENE_SERVICE)
Create an optional service for getting the complete planning scene This is useful for satisfying the ...
Definition: planning_scene_monitor.cpp:562
ros::Rate
planning_scene_monitor::PlanningSceneMonitor::getMonitoredTopics
void getMonitoredTopics(std::vector< std::string > &topics) const
Get the topic names that the monitor is listening to.
Definition: planning_scene_monitor.cpp:478
planning_scene_monitor::PlanningSceneMonitor::getUpdatedFrameTransforms
void getUpdatedFrameTransforms(std::vector< geometry_msgs::TransformStamped > &transforms)
Definition: planning_scene_monitor.cpp:1349
planning_scene_monitor::PlanningSceneMonitor::clearUpdateCallbacks
void clearUpdateCallbacks()
Clear the functions to be called when an update to the scene is received.
Definition: planning_scene_monitor.cpp:1336
planning_scene_monitor::PlanningSceneMonitor::clearOctomap
void clearOctomap()
Definition: planning_scene_monitor.cpp:589
planning_scene_monitor::PlanningSceneMonitor::UPDATE_SCENE
@ UPDATE_SCENE
The entire scene was updated.
Definition: planning_scene_monitor.h:112
DurationBase< WallDuration >::toSec
double toSec() const
collision_detection::CollisionPluginLoader::setupScene
void setupScene(ros::NodeHandle &nh, const planning_scene::PlanningScenePtr &scene)
Fetch plugin name from parameter server and activate the plugin for the given scene.
Definition: collision_plugin_loader.cpp:40
moveit::ConstructException
planning_scene_monitor::PlanningSceneMonitor::parent_scene_
planning_scene::PlanningScenePtr parent_scene_
Definition: planning_scene_monitor.h:504
profiler.h
ros::WallDuration
collision_detection::World::CREATE
CREATE
tf2::TransformException
planning_scene
planning_scene_monitor::PlanningSceneMonitor::requestPlanningSceneState
bool requestPlanningSceneState(const std::string &service_name=DEFAULT_PLANNING_SCENE_SERVICE)
Request a full planning scene state using a service call Be careful not to use this in conjunction wi...
Definition: planning_scene_monitor.cpp:529
planning_scene_monitor::PlanningSceneMonitor::startPublishingPlanningScene
void startPublishingPlanningScene(SceneUpdateType event, const std::string &planning_scene_topic=MONITORED_PLANNING_SCENE_TOPIC)
Start publishing the maintained planning scene. The first message set out is a complete planning scen...
Definition: planning_scene_monitor.cpp:376
planning_scene_monitor::PlanningSceneMonitor::monitorDiffs
void monitorDiffs(bool flag)
By default, the maintained planning scene does not reason about diffs. When the flag passed in is tru...
Definition: planning_scene_monitor.cpp:313
planning_scene_monitor::PlanningSceneMonitor::update_callbacks_
std::vector< boost::function< void(SceneUpdateType)> > update_callbacks_
Definition: planning_scene_monitor.h:571
planning_scene_monitor::PlanningSceneMonitor::UPDATE_TRANSFORMS
@ UPDATE_TRANSFORMS
The maintained set of fixed transforms in the monitored scene was updated.
Definition: planning_scene_monitor.h:105
ros::Duration
ros::NodeHandle::createWallTimer
WallTimer createWallTimer(WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
moveit::core::AttachedBody::getName
const std::string & getName() const
planning_scene_monitor::PlanningSceneMonitor::planning_scene_publisher_
ros::Publisher planning_scene_publisher_
Definition: planning_scene_monitor.h:532
t
geometry_msgs::TransformStamped t
planning_scene_monitor::PlanningSceneMonitor::link_shape_handles_
LinkShapeHandles link_shape_handles_
Definition: planning_scene_monitor.h:564
Transform.h
ros::WallTimer::stop
void stop()
planning_scene_monitor::PlanningSceneMonitor::includeWorldObjectInOctree
void includeWorldObjectInOctree(const collision_detection::World::ObjectConstPtr &obj)
Definition: planning_scene_monitor.cpp:913
XmlRpc::XmlRpcValue
planning_scene_monitor::PlanningSceneMonitor::includeAttachedBodiesInOctree
void includeAttachedBodiesInOctree()
Definition: planning_scene_monitor.cpp:798
planning_scene_monitor::PlanningSceneMonitor::scene_update_mutex_
boost::shared_mutex scene_update_mutex_
if diffs are monitored, this is the pointer to the parent scene
Definition: planning_scene_monitor.h:505
DurationBase< WallDuration >::isZero
bool isZero() const
ros::NodeHandle
planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor
PlanningSceneMonitor(const std::string &robot_description, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer=std::shared_ptr< tf2_ros::Buffer >(), const std::string &name="")
Constructor.
Definition: planning_scene_monitor.cpp:151
planning_scene_monitor::PlanningSceneMonitor::shape_transform_cache_lookup_wait_time_
ros::Duration shape_transform_cache_lookup_wait_time_
the amount of time to wait when looking up transforms
Definition: planning_scene_monitor.h:611
ros::Time::now
static Time now()
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
The name of the topic used by default for attached collision objects.
Definition: planning_scene_monitor.h:119
robot_model_loader.h
planning_scene_monitor::PlanningSceneMonitor::lockSceneWrite
void lockSceneWrite()
Lock the scene for writing (only one thread can lock for writing and no other thread can lock for rea...
Definition: planning_scene_monitor.cpp:1026


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Feb 27 2025 03:27:54