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 void PlanningSceneMonitor::initialize(const planning_scene::PlanningScenePtr& scene)
185 {
187  moveit::tools::Profiler::ScopedBlock prof_block("PlanningSceneMonitor::initialize");
188 
189  if (monitor_name_.empty())
190  monitor_name_ = "planning_scene_monitor";
191  robot_description_ = rm_loader_->getRobotDescription();
192  if (rm_loader_->getModel())
193  {
194  robot_model_ = rm_loader_->getModel();
195  scene_ = scene;
196  if (!scene_)
197  {
198  try
199  {
200  scene_ = std::make_shared<planning_scene::PlanningScene>(rm_loader_->getModel());
203 
204  scene_->getCollisionEnvNonConst()->setPadding(default_robot_padd_);
205  scene_->getCollisionEnvNonConst()->setScale(default_robot_scale_);
206  for (const std::pair<const std::string, double>& it : default_robot_link_padd_)
207  {
208  scene_->getCollisionEnvNonConst()->setLinkPadding(it.first, it.second);
209  }
210  for (const std::pair<const std::string, double>& it : default_robot_link_scale_)
211  {
212  scene_->getCollisionEnvNonConst()->setLinkScale(it.first, it.second);
213  }
214  scene_->propogateRobotPadding();
215  }
217  {
218  ROS_ERROR_NAMED(LOGNAME, "Configuration of planning scene failed");
219  scene_.reset();
220  }
221  }
222  // scene_const_ is set regardless if scene_ is null or not
224  if (scene_)
225  {
226  // The scene_ is loaded on the collision loader only if it was correctly instantiated
228  scene_->setAttachedBodyUpdateCallback([this](moveit::core::AttachedBody* body, bool attached) {
230  });
231  scene_->setCollisionObjectUpdateCallback(
232  [this](const collision_detection::World::ObjectConstPtr& object, collision_detection::World::Action action) {
233  currentWorldObjectUpdateCallback(object, action);
234  });
235  }
236  }
237  else
238  {
239  ROS_ERROR_NAMED(LOGNAME, "Robot model not loaded");
240  }
241 
244 
248 
249  double temp_wait_time = 0.05;
250 
251  if (!robot_description_.empty())
252  nh_.param(robot_description_ + "_planning/shape_transform_cache_lookup_wait_time", temp_wait_time, temp_wait_time);
253 
255 
256  state_update_pending_ = false;
258  false, // not a oneshot timer
259  false); // do not start the timer yet
260 
261  reconfigure_impl_ = new DynamicReconfigureImpl(this);
262 }
263 
265 {
266  if (scene_)
267  {
268  if (flag)
269  {
270  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
271  if (scene_)
272  {
273  scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback());
274  scene_->setCollisionObjectUpdateCallback(collision_detection::World::ObserverCallbackFn());
275  scene_->decoupleParent();
277  scene_ = parent_scene_->diff();
279  scene_->setAttachedBodyUpdateCallback([this](moveit::core::AttachedBody* body, bool attached) {
281  });
282  scene_->setCollisionObjectUpdateCallback(
283  [this](const collision_detection::World::ObjectConstPtr& object,
285  }
286  }
287  else
288  {
290  {
291  ROS_WARN_NAMED(LOGNAME, "Diff monitoring was stopped while publishing planning scene diffs. "
292  "Stopping planning scene diff publisher");
294  }
295  {
296  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
297  if (scene_)
298  {
299  scene_->decoupleParent();
300  parent_scene_.reset();
301  // remove the '+' added by .diff() at the end of the scene name
302  if (!scene_->getName().empty())
303  {
304  if (scene_->getName()[scene_->getName().length() - 1] == '+')
305  scene_->setName(scene_->getName().substr(0, scene_->getName().length() - 1));
306  }
307  }
308  }
309  }
310  }
311 }
312 
314 {
316  {
317  std::unique_ptr<boost::thread> copy;
318  copy.swap(publish_planning_scene_);
319  new_scene_update_condition_.notify_all();
320  copy->join();
321  monitorDiffs(false);
323  ROS_INFO_NAMED(LOGNAME, "Stopped publishing maintained planning scene.");
324  }
325 }
326 
327 void PlanningSceneMonitor::startPublishingPlanningScene(SceneUpdateType update_type,
328  const std::string& planning_scene_topic)
329 {
330  publish_update_types_ = update_type;
332  {
333  planning_scene_publisher_ = nh_.advertise<moveit_msgs::PlanningScene>(planning_scene_topic, 100, false);
334  ROS_INFO_NAMED(LOGNAME, "Publishing maintained planning scene on '%s'", planning_scene_topic.c_str());
335  monitorDiffs(true);
336  publish_planning_scene_ = std::make_unique<boost::thread>([this] { scenePublishingThread(); });
337  }
338 }
339 
341 {
342  ROS_DEBUG_NAMED(LOGNAME, "Started scene publishing thread ...");
343 
344  // publish the full planning scene once
345  {
346  moveit_msgs::PlanningScene msg;
347  {
349  if (octomap_monitor_)
350  lock = octomap_monitor_->getOcTreePtr()->reading();
351  scene_->getPlanningSceneMsg(msg);
352  }
354  ROS_DEBUG_NAMED(LOGNAME, "Published the full planning scene: '%s'", msg.name.c_str());
355  }
356 
357  do
358  {
359  moveit_msgs::PlanningScene msg;
360  bool publish_msg = false;
361  bool is_full = false;
363  {
364  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
366  new_scene_update_condition_.wait(ulock);
368  {
370  {
372  is_full = true;
373  else
374  {
376  if (octomap_monitor_)
377  lock = octomap_monitor_->getOcTreePtr()->reading();
378  scene_->getPlanningSceneDiffMsg(msg);
380  {
381  msg.robot_state.attached_collision_objects.clear();
382  msg.robot_state.is_diff = true;
383  }
384  }
385  boost::recursive_mutex::scoped_lock prevent_shape_cache_updates(shape_handles_lock_); // we don't want the
386  // transform cache to
387  // update while we are
388  // potentially changing
389  // attached bodies
390  scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback());
391  scene_->setCollisionObjectUpdateCallback(collision_detection::World::ObserverCallbackFn());
392  scene_->pushDiffs(parent_scene_);
393  scene_->clearDiffs();
394  scene_->setAttachedBodyUpdateCallback([this](moveit::core::AttachedBody* body, bool attached) {
396  });
397  scene_->setCollisionObjectUpdateCallback(
398  [this](const collision_detection::World::ObjectConstPtr& object,
400  if (octomap_monitor_)
401  {
402  excludeAttachedBodiesFromOctree(); // in case updates have happened to the attached bodies, put them in
403  excludeWorldObjectsFromOctree(); // in case updates have happened to the attached bodies, put them in
404  }
405  if (is_full)
406  {
408  if (octomap_monitor_)
409  lock = octomap_monitor_->getOcTreePtr()->reading();
410  scene_->getPlanningSceneMsg(msg);
411  }
412  // also publish timestamp of this robot_state
413  msg.robot_state.joint_state.header.stamp = last_robot_motion_time_;
414  publish_msg = true;
415  }
417  }
418  }
419  if (publish_msg)
420  {
422  if (is_full)
423  ROS_DEBUG_NAMED(LOGNAME, "Published full planning scene: '%s'", msg.name.c_str());
424  rate.sleep();
425  }
426  } while (publish_planning_scene_);
427 }
428 
429 void PlanningSceneMonitor::getMonitoredTopics(std::vector<std::string>& topics) const
430 {
431  topics.clear();
433  {
434  const std::string& t = current_state_monitor_->getMonitoredTopic();
435  if (!t.empty())
436  topics.push_back(t);
437  }
439  topics.push_back(planning_scene_subscriber_.getTopic());
441  topics.push_back(collision_object_subscriber_.getTopic());
443  topics.push_back(planning_scene_world_subscriber_.getTopic());
444 }
445 
446 namespace
447 {
448 bool sceneIsParentOf(const planning_scene::PlanningSceneConstPtr& scene,
449  const planning_scene::PlanningScene* possible_parent)
450 {
451  if (scene && scene.get() == possible_parent)
452  return true;
453  if (scene)
454  return sceneIsParentOf(scene->getParent(), possible_parent);
455  return false;
456 }
457 } // namespace
458 
459 bool PlanningSceneMonitor::updatesScene(const planning_scene::PlanningScenePtr& scene) const
460 {
461  return sceneIsParentOf(scene_const_, scene.get());
462 }
463 
464 bool PlanningSceneMonitor::updatesScene(const planning_scene::PlanningSceneConstPtr& scene) const
465 {
466  return sceneIsParentOf(scene_const_, scene.get());
467 }
468 
469 void PlanningSceneMonitor::triggerSceneUpdateEvent(SceneUpdateType update_type)
470 {
471  // do not modify update functions while we are calling them
472  boost::recursive_mutex::scoped_lock lock(update_lock_);
473 
474  for (boost::function<void(SceneUpdateType)>& update_callback : update_callbacks_)
475  update_callback(update_type);
476  new_scene_update_ = (SceneUpdateType)((int)new_scene_update_ | (int)update_type);
477  new_scene_update_condition_.notify_all();
478 }
479 
480 bool PlanningSceneMonitor::requestPlanningSceneState(const std::string& service_name)
481 {
482  if (get_scene_service_.getService() == service_name)
483  {
484  ROS_FATAL_STREAM_NAMED(LOGNAME, "requestPlanningSceneState() to self-provided service '" << service_name << "'");
485  throw std::runtime_error("requestPlanningSceneState() to self-provided service: " + service_name);
486  }
487  // use global namespace for service
488  ros::ServiceClient client = ros::NodeHandle().serviceClient<moveit_msgs::GetPlanningScene>(service_name);
489  // all scene components are returned if none are specified
490  moveit_msgs::GetPlanningScene srv;
491 
492  // Make sure client is connected to server
493  if (!client.exists())
494  {
495  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Waiting for service `" << service_name << "` to exist.");
497  }
498 
499  if (client.call(srv))
500  {
501  newPlanningSceneMessage(srv.response.scene);
502  }
503  else
504  {
506  LOGNAME, "Failed to call service %s, have you launched move_group or called psm.providePlanningSceneService()?",
507  service_name.c_str());
508  return false;
509  }
510  return true;
511 }
512 
513 void PlanningSceneMonitor::providePlanningSceneService(const std::string& service_name)
514 {
515  // Load the service
518 }
519 
520 bool PlanningSceneMonitor::getPlanningSceneServiceCallback(moveit_msgs::GetPlanningScene::Request& req,
521  moveit_msgs::GetPlanningScene::Response& res)
522 {
523  if (req.components.components & moveit_msgs::PlanningSceneComponents::TRANSFORMS)
525 
526  moveit_msgs::PlanningSceneComponents all_components;
527  all_components.components = UINT_MAX; // Return all scene components if nothing is specified.
528 
529  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
530  scene_->getPlanningSceneMsg(res.scene, req.components.components ? req.components : all_components);
531 
532  return true;
533 }
534 
535 void PlanningSceneMonitor::newPlanningSceneCallback(const moveit_msgs::PlanningSceneConstPtr& scene)
536 {
537  newPlanningSceneMessage(*scene);
538 }
539 
541 {
542  bool removed = false;
543  {
544  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
545  removed = scene_->getWorldNonConst()->removeObject(scene_->OCTOMAP_NS);
546 
547  if (octomap_monitor_)
548  {
549  octomap_monitor_->getOcTreePtr()->lockWrite();
550  octomap_monitor_->getOcTreePtr()->clear();
551  octomap_monitor_->getOcTreePtr()->unlockWrite();
552  }
553  else
554  {
555  ROS_WARN_NAMED(LOGNAME, "Unable to clear octomap since no octomap monitor has been initialized");
556  } // Lift the scoped lock before calling triggerSceneUpdateEvent to avoid deadlock
557  }
558 
559  if (removed)
561 }
562 
563 bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::PlanningScene& scene)
564 {
565  if (!scene_)
566  return false;
567 
568  bool result;
569 
571  std::string old_scene_name;
572  {
573  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
574  // we don't want the transform cache to update while we are potentially changing attached bodies
575  boost::recursive_mutex::scoped_lock prevent_shape_cache_updates(shape_handles_lock_);
576 
578  last_robot_motion_time_ = scene.robot_state.joint_state.header.stamp;
579  ROS_DEBUG_STREAM_NAMED("planning_scene_monitor",
580  "scene update " << fmod(last_update_time_.toSec(), 10.)
581  << " robot stamp: " << fmod(last_robot_motion_time_.toSec(), 10.));
582  old_scene_name = scene_->getName();
583 
584  if (!scene.is_diff && parent_scene_)
585  {
586  // clear maintained (diff) scene_ and set the full new scene in parent_scene_ instead
587  scene_->clearDiffs();
588  result = parent_scene_->setPlanningSceneMsg(scene);
589  // There were no callbacks for individual object changes, so rebuild the octree masks
592  }
593  else
594  {
595  result = scene_->setPlanningSceneDiffMsg(scene);
596  }
597 
598  if (octomap_monitor_)
599  {
600  if (!scene.is_diff && scene.world.octomap.octomap.data.empty())
601  {
602  octomap_monitor_->getOcTreePtr()->lockWrite();
603  octomap_monitor_->getOcTreePtr()->clear();
604  octomap_monitor_->getOcTreePtr()->unlockWrite();
605  }
606  }
607  robot_model_ = scene_->getRobotModel();
608 
609  if (octomap_monitor_)
610  {
611  excludeAttachedBodiesFromOctree(); // in case updates have happened to the attached bodies, put them in
612  excludeWorldObjectsFromOctree(); // in case updates have happened to the attached bodies, put them in
613  }
614  }
615 
616  // if we have a diff, try to more accurately determine the update type
617  if (scene.is_diff)
618  {
619  bool no_other_scene_upd = (scene.name.empty() || scene.name == old_scene_name) &&
620  scene.allowed_collision_matrix.entry_names.empty() && scene.link_padding.empty() &&
621  scene.link_scale.empty();
622  if (no_other_scene_upd)
623  {
624  upd = UPDATE_NONE;
625  if (!moveit::core::isEmpty(scene.world))
626  upd = (SceneUpdateType)((int)upd | (int)UPDATE_GEOMETRY);
627 
628  if (!scene.fixed_frame_transforms.empty())
629  upd = (SceneUpdateType)((int)upd | (int)UPDATE_TRANSFORMS);
630 
631  if (!moveit::core::isEmpty(scene.robot_state))
632  {
633  upd = (SceneUpdateType)((int)upd | (int)UPDATE_STATE);
634  if (!scene.robot_state.attached_collision_objects.empty() || !static_cast<bool>(scene.robot_state.is_diff))
635  upd = (SceneUpdateType)((int)upd | (int)UPDATE_GEOMETRY);
636  }
637  }
638  }
640  return result;
641 }
642 
643 void PlanningSceneMonitor::newPlanningSceneWorldCallback(const moveit_msgs::PlanningSceneWorldConstPtr& world)
644 {
645  if (scene_)
646  {
648  {
649  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
651  scene_->getWorldNonConst()->clearObjects();
652  scene_->processPlanningSceneWorldMsg(*world);
653  if (octomap_monitor_)
654  {
655  if (world->octomap.octomap.data.empty())
656  {
657  octomap_monitor_->getOcTreePtr()->lockWrite();
658  octomap_monitor_->getOcTreePtr()->clear();
659  octomap_monitor_->getOcTreePtr()->unlockWrite();
660  }
661  }
662  }
664  }
665 }
666 
667 void PlanningSceneMonitor::collisionObjectCallback(const moveit_msgs::CollisionObjectConstPtr& obj)
668 {
669  if (!scene_)
670  return;
671 
673  {
674  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
676  if (!scene_->processCollisionObjectMsg(*obj))
677  return;
678  }
680 }
681 
682 void PlanningSceneMonitor::attachObjectCallback(const moveit_msgs::AttachedCollisionObjectConstPtr& obj)
683 {
684  if (scene_)
685  {
687  {
688  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
690  scene_->processAttachedCollisionObjectMsg(*obj);
691  }
693  }
694 }
695 
697 {
698  if (!octomap_monitor_)
699  return;
700 
701  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
702 
704  const std::vector<const moveit::core::LinkModel*>& links = getRobotModel()->getLinkModelsWithCollisionGeometry();
706  bool warned = false;
707  for (const moveit::core::LinkModel* link : links)
708  {
709  std::vector<shapes::ShapeConstPtr> shapes = link->getShapes(); // copy shared ptrs on purpuse
710  for (std::size_t j = 0; j < shapes.size(); ++j)
711  {
712  // merge mesh vertices up to 0.1 mm apart
713  if (shapes[j]->type == shapes::MESH)
714  {
715  shapes::Mesh* m = static_cast<shapes::Mesh*>(shapes[j]->clone());
716  m->mergeVertices(1e-4);
717  shapes[j].reset(m);
718  }
719 
721  if (h)
722  link_shape_handles_[link].push_back(std::make_pair(h, j));
723  }
724  if (!warned && ((ros::WallTime::now() - start) > ros::WallDuration(30.0)))
725  {
726  ROS_WARN_STREAM_NAMED(LOGNAME, "It is likely there are too many vertices in collision geometry");
727  warned = true;
728  }
729  }
730 }
731 
733 {
734  if (!octomap_monitor_)
735  return;
736 
737  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
738 
739  for (std::pair<const moveit::core::LinkModel* const,
740  std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>& link_shape_handle :
742  for (std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>& it : link_shape_handle.second)
743  octomap_monitor_->forgetShape(it.first);
744  link_shape_handles_.clear();
745 }
746 
748 {
749  if (!octomap_monitor_)
750  return;
751 
752  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
753 
754  // clear information about any attached body, without refering to the AttachedBody* ptr (could be invalid)
755  for (std::pair<const moveit::core::AttachedBody* const,
756  std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>& attached_body_shape_handle :
758  for (std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>& it : attached_body_shape_handle.second)
759  octomap_monitor_->forgetShape(it.first);
761 }
762 
764 {
765  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
766 
768  // add attached objects again
769  std::vector<const moveit::core::AttachedBody*> ab;
770  scene_->getCurrentState().getAttachedBodies(ab);
771  for (const moveit::core::AttachedBody* body : ab)
773 }
774 
776 {
777  if (!octomap_monitor_)
778  return;
779 
780  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
781 
782  // clear information about any attached object
783  for (std::pair<const std::string, std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>>>&
784  collision_body_shape_handle : collision_body_shape_handles_)
785  for (std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>& it :
786  collision_body_shape_handle.second)
787  octomap_monitor_->forgetShape(it.first);
789 }
790 
792 {
793  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
794 
796  for (const std::pair<const std::string, collision_detection::World::ObjectPtr>& it : *scene_->getWorld())
797  excludeWorldObjectFromOctree(it.second);
798 }
799 
801 {
802  if (!octomap_monitor_)
803  return;
804 
805  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
806  bool found = false;
807  for (std::size_t i = 0; i < attached_body->getShapes().size(); ++i)
808  {
809  if (attached_body->getShapes()[i]->type == shapes::PLANE || attached_body->getShapes()[i]->type == shapes::OCTREE)
810  continue;
811  occupancy_map_monitor::ShapeHandle h = octomap_monitor_->excludeShape(attached_body->getShapes()[i]);
812  if (h)
813  {
814  found = true;
815  attached_body_shape_handles_[attached_body].push_back(std::make_pair(h, i));
816  }
817  }
818  if (found)
819  ROS_DEBUG_NAMED(LOGNAME, "Excluding attached body '%s' from monitored octomap", attached_body->getName().c_str());
820 }
821 
823 {
824  if (!octomap_monitor_)
825  return;
826 
827  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
828 
829  AttachedBodyShapeHandles::iterator it = attached_body_shape_handles_.find(attached_body);
830  if (it != attached_body_shape_handles_.end())
831  {
832  for (std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>& shape_handle : it->second)
833  octomap_monitor_->forgetShape(shape_handle.first);
834  ROS_DEBUG_NAMED(LOGNAME, "Including attached body '%s' in monitored octomap", attached_body->getName().c_str());
836  }
837 }
838 
839 void PlanningSceneMonitor::excludeWorldObjectFromOctree(const collision_detection::World::ObjectConstPtr& obj)
840 {
841  if (!octomap_monitor_)
842  return;
843 
844  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
845 
846  bool found = false;
847  for (std::size_t i = 0; i < obj->shapes_.size(); ++i)
848  {
849  if (obj->shapes_[i]->type == shapes::PLANE || obj->shapes_[i]->type == shapes::OCTREE)
850  continue;
851  occupancy_map_monitor::ShapeHandle h = octomap_monitor_->excludeShape(obj->shapes_[i]);
852  if (h)
853  {
854  collision_body_shape_handles_[obj->id_].push_back(std::make_pair(h, &obj->global_shape_poses_[i]));
855  found = true;
856  }
857  }
858  if (found)
859  ROS_DEBUG_NAMED(LOGNAME, "Excluding collision object '%s' from monitored octomap", obj->id_.c_str());
860 }
861 
862 void PlanningSceneMonitor::includeWorldObjectInOctree(const collision_detection::World::ObjectConstPtr& obj)
863 {
864  if (!octomap_monitor_)
865  return;
866 
867  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
868 
869  CollisionBodyShapeHandles::iterator it = collision_body_shape_handles_.find(obj->id_);
870  if (it != collision_body_shape_handles_.end())
871  {
872  for (std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>& shape_handle : it->second)
873  octomap_monitor_->forgetShape(shape_handle.first);
874  ROS_DEBUG_NAMED(LOGNAME, "Including collision object '%s' in monitored octomap", obj->id_.c_str());
876  }
877 }
878 
880  bool just_attached)
881 {
882  if (!octomap_monitor_)
883  return;
884 
885  if (just_attached)
886  excludeAttachedBodyFromOctree(attached_body);
887  else
888  includeAttachedBodyInOctree(attached_body);
889 }
890 
891 void PlanningSceneMonitor::currentWorldObjectUpdateCallback(const collision_detection::World::ObjectConstPtr& obj,
893 {
895  return;
897  return;
898 
901  else if (action & collision_detection::World::DESTROY)
903  else
904  {
907  }
908 }
909 
910 bool PlanningSceneMonitor::waitForCurrentRobotState(const ros::Time& t, double wait_time)
911 {
912  if (t.isZero())
913  return false;
915  ros::WallDuration timeout(wait_time);
916 
917  ROS_DEBUG_NAMED(LOGNAME, "sync robot state to: %.3fs", fmod(t.toSec(), 10.));
918 
920  {
921  // Wait for next robot update in state monitor.
922  bool success = current_state_monitor_->waitForCurrentState(t, wait_time);
923 
924  /* As robot updates are passed to the planning scene only in throttled fashion, there might
925  be still an update pending. If so, explicitly update the planning scene here.
926  If waitForCurrentState failed, we didn't get any new state updates within wait_time. */
927  if (success)
928  {
929  boost::mutex::scoped_lock lock(state_pending_mutex_);
930  if (state_update_pending_) // enforce state update
931  {
932  state_update_pending_ = false;
934  lock.unlock();
936  }
937  return true;
938  }
939 
940  ROS_WARN_NAMED(LOGNAME, "Failed to fetch current robot state.");
941  return false;
942  }
943 
944  // Sometimes there is no state monitor. In this case state updates are received as part of scene updates only.
945  // However, scene updates are only published if the robot actually moves. Hence we need a timeout!
946  // As publishing planning scene updates is throttled (2Hz by default), a 1s timeout is a suitable default.
947  boost::shared_lock<boost::shared_mutex> lock(scene_update_mutex_);
948  ros::Time prev_robot_motion_time = last_robot_motion_time_;
949  while (last_robot_motion_time_ < t && // Wait until the state update actually reaches the scene.
950  timeout > ros::WallDuration())
951  {
952  ROS_DEBUG_STREAM_NAMED(LOGNAME, "last robot motion: " << (t - last_robot_motion_time_).toSec() << " ago");
953  new_scene_update_condition_.wait_for(lock, boost::chrono::nanoseconds(timeout.toNSec()));
954  timeout -= ros::WallTime::now() - start; // compute remaining wait_time
955  }
956  bool success = last_robot_motion_time_ >= t;
957  // suppress warning if we received an update at all
958  if (!success && prev_robot_motion_time != last_robot_motion_time_)
959  ROS_WARN_NAMED(LOGNAME, "Maybe failed to update robot state, time diff: %.3fs",
960  (t - last_robot_motion_time_).toSec());
961 
962  ROS_DEBUG_STREAM_NAMED(LOGNAME, "sync done: robot motion: " << (t - last_robot_motion_time_).toSec()
963  << " scene update: " << (t - last_update_time_).toSec());
964  return success;
965 }
966 
968 {
969  scene_update_mutex_.lock_shared();
970  if (octomap_monitor_)
971  octomap_monitor_->getOcTreePtr()->lockRead();
972 }
973 
975 {
976  if (octomap_monitor_)
977  octomap_monitor_->getOcTreePtr()->unlockRead();
978  scene_update_mutex_.unlock_shared();
979 }
980 
982 {
983  scene_update_mutex_.lock();
984  if (octomap_monitor_)
985  octomap_monitor_->getOcTreePtr()->lockWrite();
986 }
987 
989 {
990  if (octomap_monitor_)
991  octomap_monitor_->getOcTreePtr()->unlockWrite();
992  scene_update_mutex_.unlock();
993 }
994 
995 void PlanningSceneMonitor::startSceneMonitor(const std::string& scene_topic)
996 {
998 
999  ROS_INFO_NAMED(LOGNAME, "Starting planning scene monitor");
1000  // listen for planning scene updates; these messages include transforms, so no need for filters
1001  if (!scene_topic.empty())
1002  {
1005  ROS_INFO_NAMED(LOGNAME, "Listening to '%s'", root_nh_.resolveName(scene_topic).c_str());
1006  }
1007 }
1008 
1010 {
1012  {
1013  ROS_INFO_NAMED(LOGNAME, "Stopping planning scene monitor");
1015  }
1016 }
1017 
1018 bool PlanningSceneMonitor::getShapeTransformCache(const std::string& target_frame, const ros::Time& target_time,
1021  if (!tf_buffer_)
1022  return false;
1023  try
1024  {
1025  boost::recursive_mutex::scoped_lock _(shape_handles_lock_);
1026 
1027  for (const std::pair<const moveit::core::LinkModel* const,
1028  std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>& link_shape_handle :
1030  {
1031  tf_buffer_->canTransform(target_frame, link_shape_handle.first->getName(), target_time,
1033  Eigen::Isometry3d ttr = tf2::transformToEigen(
1034  tf_buffer_->lookupTransform(target_frame, link_shape_handle.first->getName(), target_time));
1035  for (std::size_t j = 0; j < link_shape_handle.second.size(); ++j)
1036  cache[link_shape_handle.second[j].first] =
1037  ttr * link_shape_handle.first->getCollisionOriginTransforms()[link_shape_handle.second[j].second];
1038  }
1039  for (const std::pair<const moveit::core::AttachedBody* const,
1040  std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>&
1041  attached_body_shape_handle : attached_body_shape_handles_)
1042  {
1043  tf_buffer_->canTransform(target_frame, attached_body_shape_handle.first->getAttachedLinkName(), target_time,
1045  Eigen::Isometry3d transform = tf2::transformToEigen(tf_buffer_->lookupTransform(
1046  target_frame, attached_body_shape_handle.first->getAttachedLinkName(), target_time));
1047  for (std::size_t k = 0; k < attached_body_shape_handle.second.size(); ++k)
1048  cache[attached_body_shape_handle.second[k].first] =
1049  transform *
1050  attached_body_shape_handle.first->getShapePosesInLinkFrame()[attached_body_shape_handle.second[k].second];
1051  }
1052  {
1053  tf_buffer_->canTransform(target_frame, scene_->getPlanningFrame(), target_time,
1055  Eigen::Isometry3d transform =
1056  tf2::transformToEigen(tf_buffer_->lookupTransform(target_frame, scene_->getPlanningFrame(), target_time));
1057  for (const std::pair<const std::string,
1058  std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>>>&
1059  collision_body_shape_handle : collision_body_shape_handles_)
1060  for (const std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>& it :
1061  collision_body_shape_handle.second)
1062  cache[it.first] = transform * (*it.second);
1063  }
1064  }
1065  catch (tf2::TransformException& ex)
1066  {
1067  ROS_ERROR_THROTTLE_NAMED(1, LOGNAME, "Transform error: %s", ex.what());
1068  return false;
1069  }
1070  return true;
1071 }
1072 
1073 void PlanningSceneMonitor::startWorldGeometryMonitor(const std::string& collision_objects_topic,
1074  const std::string& planning_scene_world_topic,
1075  const bool load_octomap_monitor)
1076 {
1078  ROS_INFO_NAMED(LOGNAME, "Starting world geometry update monitor for collision objects, attached objects, octomap "
1079  "updates.");
1080 
1081  // Listen to the /collision_objects topic to detect requests to add/remove/update collision objects to/from the world
1082  if (!collision_objects_topic.empty())
1083  {
1085  root_nh_.subscribe(collision_objects_topic, 1024, &PlanningSceneMonitor::collisionObjectCallback, this);
1086  ROS_INFO_NAMED(LOGNAME, "Listening to '%s'", root_nh_.resolveName(collision_objects_topic).c_str());
1087  }
1088 
1089  if (!planning_scene_world_topic.empty())
1090  {
1092  root_nh_.subscribe(planning_scene_world_topic, 1, &PlanningSceneMonitor::newPlanningSceneWorldCallback, this);
1093  ROS_INFO_NAMED(LOGNAME, "Listening to '%s' for planning scene world geometry",
1094  root_nh_.resolveName(planning_scene_world_topic).c_str());
1095  }
1096 
1097  // Ocotomap monitor is optional
1098  if (load_octomap_monitor)
1099  {
1100  if (!octomap_monitor_)
1101  {
1103  std::make_unique<occupancy_map_monitor::OccupancyMapMonitor>(tf_buffer_, scene_->getPlanningFrame());
1107 
1108  octomap_monitor_->setTransformCacheCallback(
1109  [this](const std::string& frame, const ros::Time& stamp, occupancy_map_monitor::ShapeTransformCache& cache) {
1110  return getShapeTransformCache(frame, stamp, cache);
1111  });
1112  octomap_monitor_->setUpdateCallback([this] { octomapUpdateCallback(); });
1113  }
1114  octomap_monitor_->startMonitor();
1115  }
1116 }
1117 
1119 {
1121  {
1122  ROS_INFO_NAMED(LOGNAME, "Stopping world geometry monitor");
1124  }
1126  {
1127  ROS_INFO_NAMED(LOGNAME, "Stopping world geometry monitor");
1129  }
1130  if (octomap_monitor_)
1131  octomap_monitor_->stopMonitor();
1132 }
1133 
1134 void PlanningSceneMonitor::startStateMonitor(const std::string& joint_states_topic,
1135  const std::string& attached_objects_topic)
1136 {
1137  stopStateMonitor();
1138  if (scene_)
1139  {
1141  current_state_monitor_ = std::make_shared<CurrentStateMonitor>(getRobotModel(), tf_buffer_, root_nh_);
1142  current_state_monitor_->addUpdateCallback(
1143  [this](const sensor_msgs::JointStateConstPtr& state) { onStateUpdate(state); });
1144  current_state_monitor_->startStateMonitor(joint_states_topic);
1145 
1146  {
1147  boost::mutex::scoped_lock lock(state_pending_mutex_);
1148  if (!dt_state_update_.isZero())
1150  }
1151 
1152  if (!attached_objects_topic.empty())
1153  {
1154  // using regular message filter as there's no header
1156  root_nh_.subscribe(attached_objects_topic, 1024, &PlanningSceneMonitor::attachObjectCallback, this);
1157  ROS_INFO_NAMED(LOGNAME, "Listening to '%s' for attached collision objects",
1158  root_nh_.resolveName(attached_objects_topic).c_str());
1159  }
1160  }
1161  else
1162  ROS_ERROR_NAMED(LOGNAME, "Cannot monitor robot state because planning scene is not configured");
1163 }
1164 
1168  current_state_monitor_->stopStateMonitor();
1171 
1172  // stop must be called with state_pending_mutex_ unlocked to avoid deadlock
1174  {
1175  boost::mutex::scoped_lock lock(state_pending_mutex_);
1176  state_update_pending_ = false;
1177  }
1178 }
1179 
1180 void PlanningSceneMonitor::onStateUpdate(const sensor_msgs::JointStateConstPtr& /* joint_state */)
1181 {
1182  const ros::WallTime& n = ros::WallTime::now();
1184 
1185  bool update = false;
1186  {
1187  boost::mutex::scoped_lock lock(state_pending_mutex_);
1188 
1189  if (dt < dt_state_update_)
1190  {
1191  state_update_pending_ = true;
1192  }
1193  else
1194  {
1195  state_update_pending_ = false;
1197  update = true;
1198  }
1199  }
1200  // run the state update with state_pending_mutex_ unlocked
1201  if (update)
1203 }
1204 
1206 {
1208  {
1209  bool update = false;
1210 
1211  const ros::WallTime& n = ros::WallTime::now();
1213 
1214  {
1215  // lock for access to dt_state_update_ and state_update_pending_
1216  boost::mutex::scoped_lock lock(state_pending_mutex_);
1218  {
1219  state_update_pending_ = false;
1221  update = true;
1223  "performPendingStateUpdate: " << fmod(last_robot_state_update_wall_time_.toSec(), 10));
1224  }
1225  }
1226 
1227  // run the state update with state_pending_mutex_ unlocked
1228  if (update)
1229  {
1231  ROS_DEBUG_NAMED(LOGNAME, "performPendingStateUpdate done");
1232  }
1233  }
1234 }
1235 
1238  if (!octomap_monitor_)
1239  return;
1240 
1242  {
1243  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
1245  octomap_monitor_->getOcTreePtr()->lockRead();
1246  try
1247  {
1248  scene_->processOctomapPtr(octomap_monitor_->getOcTreePtr(), Eigen::Isometry3d::Identity());
1249  octomap_monitor_->getOcTreePtr()->unlockRead();
1250  }
1251  catch (...)
1252  {
1253  octomap_monitor_->getOcTreePtr()->unlockRead(); // unlock and rethrow
1254  throw;
1255  }
1256  }
1258 }
1259 
1261 {
1262  bool update = false;
1263  if (hz > std::numeric_limits<double>::epsilon())
1264  {
1265  boost::mutex::scoped_lock lock(state_pending_mutex_);
1266  dt_state_update_.fromSec(1.0 / hz);
1269  }
1270  else
1271  {
1272  // stop must be called with state_pending_mutex_ unlocked to avoid deadlock
1274  boost::mutex::scoped_lock lock(state_pending_mutex_);
1277  update = true;
1278  }
1279  ROS_INFO_NAMED(LOGNAME, "Updating internal planning scene state at most every %lf seconds", dt_state_update_.toSec());
1280 
1281  if (update)
1283 }
1284 
1286 {
1288  {
1289  std::vector<std::string> missing;
1290  if (!current_state_monitor_->haveCompleteState(missing) &&
1291  (ros::Time::now() - current_state_monitor_->getMonitorStartTime()).toSec() > 1.0)
1292  {
1293  std::string missing_str = boost::algorithm::join(missing, ", ");
1294  ROS_WARN_THROTTLE_NAMED(1, LOGNAME, "The complete state of the robot is not yet known. Missing %s",
1295  missing_str.c_str());
1296  }
1297 
1298  {
1299  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
1301  ROS_DEBUG_STREAM_NAMED(LOGNAME, "robot state update " << fmod(last_robot_motion_time_.toSec(), 10.));
1302  current_state_monitor_->setToCurrentState(scene_->getCurrentStateNonConst());
1303  scene_->getCurrentStateNonConst().update(); // compute all transforms
1304  }
1306  }
1307  else
1308  ROS_ERROR_THROTTLE_NAMED(1, LOGNAME, "State monitor is not active. Unable to set the planning scene state");
1309 }
1310 
1311 void PlanningSceneMonitor::addUpdateCallback(const boost::function<void(SceneUpdateType)>& fn)
1312 {
1313  boost::recursive_mutex::scoped_lock lock(update_lock_);
1314  if (fn)
1315  update_callbacks_.push_back(fn);
1316 }
1319 {
1320  boost::recursive_mutex::scoped_lock lock(update_lock_);
1321  update_callbacks_.clear();
1322 }
1323 
1325 {
1327  ROS_DEBUG_NAMED(LOGNAME, "Maximum frequency for publishing a planning scene is now %lf Hz",
1329 }
1330 
1331 void PlanningSceneMonitor::getUpdatedFrameTransforms(std::vector<geometry_msgs::TransformStamped>& transforms)
1332 {
1333  const std::string& target = getRobotModel()->getModelFrame();
1334 
1335  std::vector<std::string> all_frame_names;
1336  tf_buffer_->_getFrameStrings(all_frame_names);
1337  for (const std::string& all_frame_name : all_frame_names)
1338  {
1339  if (all_frame_name == target || getRobotModel()->hasLinkModel(all_frame_name))
1340  continue;
1341 
1342  geometry_msgs::TransformStamped f;
1343  try
1344  {
1345  f = tf_buffer_->lookupTransform(target, all_frame_name, ros::Time(0));
1346  }
1347  catch (tf2::TransformException& ex)
1348  {
1349  ROS_WARN_STREAM_NAMED(LOGNAME, "Unable to transform object from frame '"
1350  << all_frame_name << "' to planning frame '" << target << "' (" << ex.what()
1351  << ")");
1352  continue;
1353  }
1354  f.header.frame_id = all_frame_name;
1355  f.child_frame_id = target;
1356  transforms.push_back(f);
1357  }
1358 }
1359 
1361 {
1362  if (!tf_buffer_)
1363  return;
1364 
1365  if (scene_)
1366  {
1367  std::vector<geometry_msgs::TransformStamped> transforms;
1368  getUpdatedFrameTransforms(transforms);
1369  {
1370  boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
1371  scene_->getTransformsNonConst().setTransforms(transforms);
1373  }
1375  }
1376 }
1377 
1379 {
1380  if (octomap_monitor_)
1381  octomap_monitor_->publishDebugInformation(flag);
1382 }
1383 
1384 void PlanningSceneMonitor::configureCollisionMatrix(const planning_scene::PlanningScenePtr& scene)
1385 {
1386  if (!scene || robot_description_.empty())
1387  return;
1388  collision_detection::AllowedCollisionMatrix& acm = scene->getAllowedCollisionMatrixNonConst();
1389 
1390  // read overriding values from the param server
1391 
1392  // first we do default collision operations
1393  if (!nh_.hasParam(robot_description_ + "_planning/default_collision_operations"))
1394  ROS_DEBUG_NAMED(LOGNAME, "No additional default collision operations specified");
1395  else
1396  {
1397  ROS_DEBUG_NAMED(LOGNAME, "Reading additional default collision operations");
1398 
1399  XmlRpc::XmlRpcValue coll_ops;
1400  nh_.getParam(robot_description_ + "_planning/default_collision_operations", coll_ops);
1401 
1402  if (coll_ops.getType() != XmlRpc::XmlRpcValue::TypeArray)
1403  {
1404  ROS_WARN_NAMED(LOGNAME, "default_collision_operations is not an array");
1405  return;
1406  }
1407 
1408  if (coll_ops.size() == 0)
1409  {
1410  ROS_WARN_NAMED(LOGNAME, "No collision operations in default collision operations");
1411  return;
1412  }
1413 
1414  for (int i = 0; i < coll_ops.size(); ++i) // NOLINT(modernize-loop-convert)
1415  {
1416  if (!coll_ops[i].hasMember("object1") || !coll_ops[i].hasMember("object2") || !coll_ops[i].hasMember("operation"))
1417  {
1418  ROS_WARN_NAMED(LOGNAME, "All collision operations must have two objects and an operation");
1419  continue;
1420  }
1421  acm.setEntry(std::string(coll_ops[i]["object1"]), std::string(coll_ops[i]["object2"]),
1422  std::string(coll_ops[i]["operation"]) == "disable");
1423  }
1424  }
1425 }
1426 
1428 {
1429  if (robot_description_.empty())
1430  {
1431  default_robot_padd_ = 0.0;
1432  default_robot_scale_ = 1.0;
1433  default_object_padd_ = 0.0;
1434  default_attached_padd_ = 0.0;
1435  return;
1436  }
1437 
1438  // print deprecation warning if necessary
1439  // TODO: remove this warning after 06/2022
1440  const std::string old_robot_description =
1441  (robot_description_[0] == '/') ? robot_description_.substr(1) : robot_description_;
1442  if (nh_.resolveName(old_robot_description) != nh_.resolveName(robot_description_))
1443  {
1444  if (nh_.hasParam(old_robot_description + "_planning/default_robot_padding") ||
1445  nh_.hasParam(old_robot_description + "_planning/default_robot_scale") ||
1446  nh_.hasParam(old_robot_description + "_planning/default_object_padding") ||
1447  nh_.hasParam(old_robot_description + "_planning/default_attached_padding") ||
1448  nh_.hasParam(old_robot_description + "_planning/default_robot_link_padding") ||
1449  nh_.hasParam(old_robot_description + "_planning/default_robot_link_scale"))
1450  {
1451  ROS_WARN_STREAM_NAMED(LOGNAME, "The path for the padding parameters has changed!\n"
1452  "Old parameter path: '"
1453  << nh_.resolveName(old_robot_description + "_planning/")
1454  << "'\n"
1455  "New parameter path: '"
1456  << nh_.resolveName(robot_description_ + "_planning/")
1457  << "'\n"
1458  "Ignoring old parameters. Please update your moveit config!");
1459  }
1460  }
1461 
1462  nh_.param(robot_description_ + "_planning/default_robot_padding", default_robot_padd_, 0.0);
1463  nh_.param(robot_description_ + "_planning/default_robot_scale", default_robot_scale_, 1.0);
1464  nh_.param(robot_description_ + "_planning/default_object_padding", default_object_padd_, 0.0);
1465  nh_.param(robot_description_ + "_planning/default_attached_padding", default_attached_padd_, 0.0);
1466  nh_.param(robot_description_ + "_planning/default_robot_link_padding", default_robot_link_padd_,
1467  std::map<std::string, double>());
1468  nh_.param(robot_description_ + "_planning/default_robot_link_scale", default_robot_link_scale_,
1469  std::map<std::string, double>());
1470 
1471  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Loaded " << default_robot_link_padd_.size() << " default link paddings");
1472  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Loaded " << default_robot_link_scale_.size() << " default link scales");
1473 }
1474 } // namespace planning_scene_monitor
planning_scene_monitor::PlanningSceneMonitor::excludeWorldObjectFromOctree
void excludeWorldObjectFromOctree(const collision_detection::World::ObjectConstPtr &obj)
Definition: planning_scene_monitor.cpp:871
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:536
moveit::core::LinkModel
planning_scene_monitor::PlanningSceneMonitor::collision_body_shape_handles_
CollisionBodyShapeHandles collision_body_shape_handles_
Definition: planning_scene_monitor.h:561
planning_scene_monitor::PlanningSceneMonitor::publishDebugInformation
void publishDebugInformation(bool flag)
Definition: planning_scene_monitor.cpp:1410
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:1212
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:923
planning_scene_monitor::PlanningSceneMonitor::default_attached_padd_
double default_attached_padd_
default attached padding
Definition: planning_scene_monitor.h:520
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:522
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:1459
shapes
planning_scene_monitor::PlanningSceneMonitor::attached_body_shape_handles_
AttachedBodyShapeHandles attached_body_shape_handles_
Definition: planning_scene_monitor.h:560
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:501
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:1050
planning_scene_monitor::PlanningSceneMonitor::stopStateMonitor
void stopStateMonitor()
Stop the state monitor.
Definition: planning_scene_monitor.cpp:1197
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:496
planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneMessage
bool newPlanningSceneMessage(const moveit_msgs::PlanningScene &scene)
Definition: planning_scene_monitor.cpp:595
planning_scene_monitor::PlanningSceneMonitor::octomapUpdateCallback
void octomapUpdateCallback()
Callback for octomap updates.
Definition: planning_scene_monitor.cpp:1268
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:1343
planning_scene_monitor::PlanningSceneMonitor::spinner_
std::shared_ptr< ros::AsyncSpinner > spinner_
Definition: planning_scene_monitor.h:507
ros::ServiceClient::exists
bool exists()
shapes::PLANE
PLANE
tf2_eigen.h
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
ros
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:616
planning_scene_monitor::PlanningSceneMonitor::scenePublishingThread
void scenePublishingThread()
Definition: planning_scene_monitor.cpp:372
planning_scene_monitor::PlanningSceneMonitor::default_robot_padd_
double default_robot_padd_
default robot padding
Definition: planning_scene_monitor.h:514
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:538
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:1292
planning_scene_monitor::PlanningSceneMonitor::collisionObjectCallback
void collisionObjectCallback(const moveit_msgs::CollisionObjectConstPtr &obj)
Callback for a new collision object msg.
Definition: planning_scene_monitor.cpp:699
planning_scene_monitor::PlanningSceneMonitor::scene_const_
planning_scene::PlanningSceneConstPtr scene_const_
Definition: planning_scene_monitor.h:498
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:565
TimeBase< Time, Duration >::toSec
double toSec() const
planning_scene_monitor::PlanningSceneMonitor::collision_object_subscriber_
ros::Subscriber collision_object_subscriber_
Definition: planning_scene_monitor.h:539
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
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:1392
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:823
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:502
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:613
planning_scene_monitor::PlanningSceneMonitor::new_scene_update_
SceneUpdateType new_scene_update_
Definition: planning_scene_monitor.h:531
planning_scene_monitor::PlanningSceneMonitor::tf_buffer_
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
Definition: planning_scene_monitor.h:509
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:607
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:516
planning_scene_monitor::PlanningSceneMonitor::state_pending_mutex_
boost::mutex state_pending_mutex_
Definition: planning_scene_monitor.h:589
planning_scene_monitor::PlanningSceneMonitor::initialize
void initialize(const planning_scene::PlanningScenePtr &scene)
Initialize the planning scene monitor.
Definition: planning_scene_monitor.cpp:216
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:530
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:546
planning_scene_monitor::PlanningSceneMonitor::updateSceneWithCurrentState
void updateSceneWithCurrentState()
Update the scene using the monitored state. This function is automatically called when an update to t...
Definition: planning_scene_monitor.cpp:1317
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:501
planning_scene_monitor::PlanningSceneMonitor::new_scene_update_condition_
boost::condition_variable_any new_scene_update_condition_
Definition: planning_scene_monitor.h:532
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:999
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:1006
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:505
planning_scene_monitor::PlanningSceneMonitor::current_state_monitor_
CurrentStateMonitorPtr current_state_monitor_
Definition: planning_scene_monitor.h:549
ros::WallTime::now
static WallTime now()
planning_scene_monitor::PlanningSceneMonitor::stopPublishingPlanningScene
void stopPublishingPlanningScene()
Stop publishing the maintained planning scene.
Definition: planning_scene_monitor.cpp:345
planning_scene_monitor::PlanningSceneMonitor::excludeAttachedBodyFromOctree
void excludeAttachedBodyFromOctree(const moveit::core::AttachedBody *attached_body)
Definition: planning_scene_monitor.cpp:832
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:618
planning_scene_monitor::PlanningSceneMonitor::queue_
ros::CallbackQueue queue_
Definition: planning_scene_monitor.h:506
planning_scene_monitor::PlanningSceneMonitor::stopSceneMonitor
void stopSceneMonitor()
Stop the scene monitor.
Definition: planning_scene_monitor.cpp:1041
planning_scene_monitor::PlanningSceneMonitor::stopWorldGeometryMonitor
void stopWorldGeometryMonitor()
Stop the world geometry monitor.
Definition: planning_scene_monitor.cpp:1150
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:1166
planning_scene_monitor::PlanningSceneMonitor::excludeRobotLinksFromOctree
void excludeRobotLinksFromOctree()
Definition: planning_scene_monitor.cpp:728
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:552
planning_scene_monitor::PlanningSceneMonitor::publish_planning_scene_
std::unique_ptr< boost::thread > publish_planning_scene_
Definition: planning_scene_monitor.h:528
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:611
planning_scene_monitor::PlanningSceneMonitor::get_scene_service_
ros::ServiceServer get_scene_service_
Definition: planning_scene_monitor.h:543
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:1020
planning_scene_monitor::PlanningSceneMonitor::robot_description_
std::string robot_description_
Definition: planning_scene_monitor.h:511
planning_scene_monitor::PlanningSceneMonitor::default_object_padd_
double default_object_padd_
default object padding
Definition: planning_scene_monitor.h:518
planning_scene_monitor::PlanningSceneMonitor::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: planning_scene_monitor.h:614
planning_scene_monitor::PlanningSceneMonitor::includeAttachedBodyInOctree
void includeAttachedBodyInOctree(const moveit::core::AttachedBody *attached_body)
Definition: planning_scene_monitor.cpp:854
planning_scene_monitor::PlanningSceneMonitor::stateUpdateTimerCallback
void stateUpdateTimerCallback(const ros::WallTimerEvent &event)
Definition: planning_scene_monitor.cpp:1237
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:1356
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:524
planning_scene_monitor::PlanningSceneMonitor::monitor_name_
std::string monitor_name_
The name of this scene monitor.
Definition: planning_scene_monitor.h:495
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:529
XmlRpc::XmlRpcValue::getType
const Type & getType() const
ROS_WARN_THROTTLE_NAMED
#define ROS_WARN_THROTTLE_NAMED(period, name,...)
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:562
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:1105
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_monitor::PlanningSceneMonitor::scene_
planning_scene::PlanningScenePtr scene_
Definition: planning_scene_monitor.h:497
planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneWorldCallback
void newPlanningSceneWorldCallback(const moveit_msgs::PlanningSceneWorldConstPtr &world)
Callback for a new planning scene world.
Definition: planning_scene_monitor.cpp:675
planning_scene_monitor::PlanningSceneMonitor::nh_
ros::NodeHandle nh_
Last time the robot has moved.
Definition: planning_scene_monitor.h:504
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:911
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:764
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:942
DurationBase< WallDuration >::toNSec
int64_t toNSec() const
planning_scene_monitor::PlanningSceneMonitor::state_update_pending_
volatile bool state_update_pending_
True when we need to update the RobotState from current_state_monitor_.
Definition: planning_scene_monitor.h:593
planning_scene_monitor::PlanningSceneMonitor::attachObjectCallback
void attachObjectCallback(const moveit_msgs::AttachedCollisionObjectConstPtr &obj)
Callback for a new attached object msg.
Definition: planning_scene_monitor.cpp:714
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:1027
std
planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneCallback
void newPlanningSceneCallback(const moveit_msgs::PlanningSceneConstPtr &scene)
Definition: planning_scene_monitor.cpp:567
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:535
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:807
moveit::tools::Profiler::ScopedBlock
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
planning_scene_monitor::PlanningSceneMonitor::excludeAttachedBodiesFromOctree
void excludeAttachedBodiesFromOctree()
Definition: planning_scene_monitor.cpp:795
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:1416
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:597
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:545
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:461
planning_scene_monitor::PlanningSceneMonitor::getUpdatedFrameTransforms
void getUpdatedFrameTransforms(std::vector< geometry_msgs::TransformStamped > &transforms)
Definition: planning_scene_monitor.cpp:1363
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:1350
planning_scene_monitor::PlanningSceneMonitor::clearOctomap
void clearOctomap()
Definition: planning_scene_monitor.cpp:572
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:499
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:512
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:359
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:296
planning_scene_monitor::PlanningSceneMonitor::update_callbacks_
std::vector< boost::function< void(SceneUpdateType)> > update_callbacks_
Definition: planning_scene_monitor.h:566
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:527
t
geometry_msgs::TransformStamped t
planning_scene_monitor::PlanningSceneMonitor::link_shape_handles_
LinkShapeHandles link_shape_handles_
Definition: planning_scene_monitor.h:559
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:894
XmlRpc::XmlRpcValue
planning_scene_monitor::PlanningSceneMonitor::includeAttachedBodiesInOctree
void includeAttachedBodiesInOctree()
Definition: planning_scene_monitor.cpp:779
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:500
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:602
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:1013


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Apr 18 2024 02:24:19