moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_scene_monitor.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
39 #include <rclcpp/rclcpp.hpp>
40 #include <tf2_ros/buffer.h>
41 #include <tf2_ros/transform_listener.h>
48 #include <moveit_msgs/srv/get_planning_scene.hpp>
49 #include <memory>
50 #include <thread>
51 #include <shared_mutex>
52 #include <mutex>
53 #include <thread>
54 
55 #include <moveit_planning_scene_monitor_export.h>
56 
57 namespace planning_scene_monitor
58 {
59 MOVEIT_CLASS_FORWARD(PlanningSceneMonitor); // Defines PlanningSceneMonitorPtr, ConstPtr, WeakPtr... etc
60 
64 class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor
65 {
66 public:
71 
76 
78  {
80  UPDATE_NONE = 0,
81 
83  UPDATE_STATE = 1,
84 
86  UPDATE_TRANSFORMS = 2,
87 
90  UPDATE_GEOMETRY = 4,
91 
93  UPDATE_SCENE = 8 + UPDATE_STATE + UPDATE_TRANSFORMS + UPDATE_GEOMETRY
94  };
95 
97  static const std::string DEFAULT_JOINT_STATES_TOPIC; // "/joint_states"
98 
100  static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC; // "/attached_collision_object"
101 
103  static const std::string DEFAULT_COLLISION_OBJECT_TOPIC; // "/collision_object"
104 
107  static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC; // "/planning_scene_world"
108 
110  static const std::string DEFAULT_PLANNING_SCENE_TOPIC; // "/planning_scene"
111 
113  static const std::string DEFAULT_PLANNING_SCENE_SERVICE; // "/get_planning_scene"
114 
117  static const std::string MONITORED_PLANNING_SCENE_TOPIC; // "monitored_planning_scene"
118 
124  [[deprecated("Passing tf2_ros::Buffer to PlanningSceneMonitor's constructor is deprecated")]] PlanningSceneMonitor(
125  const rclcpp::Node::SharedPtr& node, const std::string& robot_description,
126  const std::shared_ptr<tf2_ros::Buffer>& /* unused */, const std::string& name = "")
127  : PlanningSceneMonitor(node, robot_description, name)
128  {
129  }
130  PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node, const std::string& robot_description,
131  const std::string& name = "");
132 
138  [[deprecated("Passing tf2_ros::Buffer to PlanningSceneMonitor's constructor is deprecated")]] PlanningSceneMonitor(
139  const rclcpp::Node::SharedPtr& node, const robot_model_loader::RobotModelLoaderPtr& rml,
140  const std::shared_ptr<tf2_ros::Buffer>& /* unused */, const std::string& name = "")
141  : PlanningSceneMonitor(node, rml, name)
142  {
143  }
144  PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node, const robot_model_loader::RobotModelLoaderPtr& rml,
145  const std::string& name = "");
146 
153  [[deprecated("Passing tf2_ros::Buffer to PlanningSceneMonitor's constructor is deprecated")]] PlanningSceneMonitor(
154  const rclcpp::Node::SharedPtr& node, const planning_scene::PlanningScenePtr& scene,
155  const std::string& robot_description, const std::shared_ptr<tf2_ros::Buffer>& /* unused */,
156  const std::string& name = "")
157  : PlanningSceneMonitor(node, scene, robot_description, name)
158  {
159  }
160  PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node, const planning_scene::PlanningScenePtr& scene,
161  const std::string& robot_description, const std::string& name = "");
162 
169  [[deprecated("Passing tf2_ros::Buffer to PlanningSceneMonitor's constructor is deprecated")]] PlanningSceneMonitor(
170  const rclcpp::Node::SharedPtr& node, const planning_scene::PlanningScenePtr& scene,
171  const robot_model_loader::RobotModelLoaderPtr& rml, const std::shared_ptr<tf2_ros::Buffer>& /* unused */,
172  const std::string& name = "")
173  : PlanningSceneMonitor(node, scene, rml, name)
174  {
175  }
176  PlanningSceneMonitor(const rclcpp::Node::SharedPtr& node, const planning_scene::PlanningScenePtr& scene,
177  const robot_model_loader::RobotModelLoaderPtr& rml, const std::string& name = "");
178 
180 
182  const std::string& getName() const
183  {
184  return monitor_name_;
185  }
186 
188  const robot_model_loader::RobotModelLoaderPtr& getRobotModelLoader() const
189  {
190  return rm_loader_;
191  }
192 
193  const moveit::core::RobotModelConstPtr& getRobotModel() const
194  {
195  return robot_model_;
196  }
197 
212  const planning_scene::PlanningScenePtr& getPlanningScene()
213  {
214  return scene_;
215  }
216 
220  const planning_scene::PlanningSceneConstPtr& getPlanningScene() const
221  {
222  return scene_const_;
223  }
224 
226  planning_scene::PlanningScenePtr
227  copyPlanningScene(const moveit_msgs::msg::PlanningScene& diff = moveit_msgs::msg::PlanningScene());
228 
233  bool updatesScene(const planning_scene::PlanningSceneConstPtr& scene) const;
234 
239  bool updatesScene(const planning_scene::PlanningScenePtr& scene) const;
240 
243  const std::string& getRobotDescription() const
244  {
245  return robot_description_;
246  }
247 
249  double getDefaultRobotPadding() const
250  {
251  return default_robot_padd_;
252  }
253 
255  double getDefaultRobotScale() const
256  {
257  return default_robot_scale_;
258  }
259 
261  double getDefaultObjectPadding() const
262  {
263  return default_object_padd_;
264  }
265 
268  {
269  return default_attached_padd_;
270  }
271 
273  const std::shared_ptr<tf2_ros::Buffer>& getTFClient() const
274  {
275  return tf_buffer_;
276  }
277 
283  void monitorDiffs(bool flag);
284 
288  void startPublishingPlanningScene(SceneUpdateType event,
289  const std::string& planning_scene_topic = MONITORED_PLANNING_SCENE_TOPIC);
290 
292  void stopPublishingPlanningScene();
293 
295  void setPlanningScenePublishingFrequency(double hz);
296 
299  {
300  return publish_planning_scene_frequency_;
301  }
302 
305  const CurrentStateMonitorPtr& getStateMonitor() const
306  {
307  return current_state_monitor_;
308  }
309 
310  CurrentStateMonitorPtr& getStateMonitorNonConst()
311  {
312  return current_state_monitor_;
313  }
314 
320  void updateFrameTransforms();
321 
325  void startStateMonitor(const std::string& joint_states_topic = DEFAULT_JOINT_STATES_TOPIC,
326  const std::string& attached_objects_topic = DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC);
327 
329  void stopStateMonitor();
330 
335  void updateSceneWithCurrentState(bool skip_update_if_locked = false);
336 
342  void setStateUpdateFrequency(double hz);
343 
345  double getStateUpdateFrequency() const
346  {
347  if (dt_state_update_.count() > 0.0)
348  return 1.0 / dt_state_update_.count();
349  else
350  return 0.0;
351  }
352 
356  void startSceneMonitor(const std::string& scene_topic = DEFAULT_PLANNING_SCENE_TOPIC);
357 
365  bool requestPlanningSceneState(const std::string& service_name = DEFAULT_PLANNING_SCENE_SERVICE);
366 
374  void providePlanningSceneService(const std::string& service_name = DEFAULT_PLANNING_SCENE_SERVICE);
375 
377  void stopSceneMonitor();
378 
387  void startWorldGeometryMonitor(const std::string& collision_objects_topic = DEFAULT_COLLISION_OBJECT_TOPIC,
388  const std::string& planning_scene_world_topic = DEFAULT_PLANNING_SCENE_WORLD_TOPIC,
389  const bool load_octomap_monitor = true);
390 
392  void stopWorldGeometryMonitor();
393 
395  void addUpdateCallback(const std::function<void(SceneUpdateType)>& fn);
396 
398  void clearUpdateCallbacks();
399 
401  void getMonitoredTopics(std::vector<std::string>& topics) const;
402 
404  const rclcpp::Time& getLastUpdateTime() const
405  {
406  return last_update_time_;
407  }
408 
409  void publishDebugInformation(bool flag);
410 
412  void triggerSceneUpdateEvent(SceneUpdateType update_type);
413 
419  bool waitForCurrentRobotState(const rclcpp::Time& t, double wait_time = 1.);
420 
421  void clearOctomap();
422 
423  // Called to update the planning scene with a new message.
424  bool newPlanningSceneMessage(const moveit_msgs::msg::PlanningScene& scene);
425 
426 protected:
430  void initialize(const planning_scene::PlanningScenePtr& scene);
431 
433  void lockSceneRead();
434 
436  void unlockSceneRead();
437 
440  void lockSceneWrite();
441 
444  void unlockSceneWrite();
445 
447  void configureCollisionMatrix(const planning_scene::PlanningScenePtr& scene);
448 
450  void configureDefaultPadding();
451 
453  void collisionObjectCallback(const moveit_msgs::msg::CollisionObject::ConstSharedPtr& obj);
454 
456  void newPlanningSceneWorldCallback(const moveit_msgs::msg::PlanningSceneWorld::ConstSharedPtr& world);
457 
459  void octomapUpdateCallback();
460 
462  void attachObjectCallback(const moveit_msgs::msg::AttachedCollisionObject::ConstSharedPtr& obj);
463 
465  void currentStateAttachedBodyUpdateCallback(moveit::core::AttachedBody* attached_body, bool just_attached);
466 
468  void currentWorldObjectUpdateCallback(const collision_detection::World::ObjectConstPtr& object,
470 
471  void includeRobotLinksInOctree();
472  void excludeRobotLinksFromOctree();
473 
474  void excludeWorldObjectsFromOctree();
475  void includeWorldObjectsInOctree();
476  void excludeWorldObjectFromOctree(const collision_detection::World::ObjectConstPtr& obj);
477  void includeWorldObjectInOctree(const collision_detection::World::ObjectConstPtr& obj);
478 
479  void excludeAttachedBodiesFromOctree();
480  void includeAttachedBodiesInOctree();
481  void excludeAttachedBodyFromOctree(const moveit::core::AttachedBody* attached_body);
482  void includeAttachedBodyInOctree(const moveit::core::AttachedBody* attached_body);
483 
484  bool getShapeTransformCache(const std::string& target_frame, const rclcpp::Time& target_time,
486 
488  std::string monitor_name_;
489 
490  planning_scene::PlanningScenePtr scene_;
491  planning_scene::PlanningSceneConstPtr scene_const_;
492  planning_scene::PlanningScenePtr parent_scene_;
493  std::shared_mutex scene_update_mutex_;
494  rclcpp::Time last_update_time_;
495  rclcpp::Time last_robot_motion_time_;
496 
497  std::shared_ptr<rclcpp::Node> node_;
498 
499  // TODO: (anasarrak) callbacks on ROS2?
500  // https://answers.ros.org/question/300874/how-do-you-use-callbackgroups-as-a-replacement-for-callbackqueues-in-ros2/
501  // ros::CallbackQueue queue_;
502  std::shared_ptr<rclcpp::Node> pnode_;
503  std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> private_executor_;
505 
506  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
507  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
508 
509  std::string robot_description_;
510 
520  std::map<std::string, double> default_robot_link_padd_;
522  std::map<std::string, double> default_robot_link_scale_;
523 
524  // variables for planning scene publishing
525  rclcpp::Publisher<moveit_msgs::msg::PlanningScene>::SharedPtr planning_scene_publisher_;
526  std::unique_ptr<std::thread> publish_planning_scene_;
529  std::atomic<SceneUpdateType> new_scene_update_;
530  std::condition_variable_any new_scene_update_condition_;
531 
532  // subscribe to various sources of data
533  rclcpp::Subscription<moveit_msgs::msg::PlanningScene>::SharedPtr planning_scene_subscriber_;
534  rclcpp::Subscription<moveit_msgs::msg::PlanningSceneWorld>::SharedPtr planning_scene_world_subscriber_;
535 
536  rclcpp::Subscription<moveit_msgs::msg::AttachedCollisionObject>::SharedPtr attached_collision_object_subscriber_;
537  rclcpp::Subscription<moveit_msgs::msg::CollisionObject>::SharedPtr collision_object_subscriber_;
538 
539  // provide an optional service to get the full planning scene state
540  // this is used by MoveGroup and related application nodes
541  rclcpp::Service<moveit_msgs::srv::GetPlanningScene>::SharedPtr get_scene_service_;
542 
543  // include a octomap monitor
544  std::unique_ptr<occupancy_map_monitor::OccupancyMapMonitor> octomap_monitor_;
545 
546  // include a current state monitor
547  CurrentStateMonitorPtr current_state_monitor_;
548 
549  typedef std::map<const moveit::core::LinkModel*,
550  std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t> > >
553  std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t> > >;
555  std::map<std::string, std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*> > >;
556 
560  mutable std::recursive_mutex shape_handles_lock_;
561 
563  std::recursive_mutex update_lock_;
564  std::vector<std::function<void(SceneUpdateType)> > update_callbacks_;
566 
567 private:
568  void getUpdatedFrameTransforms(std::vector<geometry_msgs::msg::TransformStamped>& transforms);
569 
570  // publish planning scene update diffs (runs in its own thread)
571  void scenePublishingThread();
572 
573  // called by current_state_monitor_ when robot state (as monitored on joint state topic) changes
574  void onStateUpdate(const sensor_msgs::msg::JointState::ConstSharedPtr& joint_state);
575 
576  // called by state_update_timer_ when a state update it pending
577  void stateUpdateTimerCallback();
578 
579  // Callback for a new planning scene msg
580  void newPlanningSceneCallback(const moveit_msgs::msg::PlanningScene::ConstSharedPtr& scene);
581 
582  // Callback for requesting the full planning scene via service
583  void getPlanningSceneServiceCallback(const moveit_msgs::srv::GetPlanningScene::Request::SharedPtr& req,
584  const moveit_msgs::srv::GetPlanningScene::Response::SharedPtr& res);
585 
586  void updatePublishSettings(bool publish_geom_updates, bool publish_state_updates, bool publish_transform_updates,
587  bool publish_planning_scene, double publish_planning_scene_hz);
588 
590  std::atomic<bool> state_update_pending_;
591 
592  // Lock for writing last_robot_state_update_wall_time_ and dt_state_update_
593  std::mutex state_update_mutex_;
594 
596  // Only access this from callback functions (and constructor)
597  // This field is protected by state_update_mutex_
598  std::chrono::system_clock::time_point last_robot_state_update_wall_time_;
599 
601  // This field is protected by state_update_mutex_
602  std::chrono::duration<double> dt_state_update_; // 1hz
603 
605  // Setting this to a non-zero value resolves issues when the sensor data is
606  // arriving so fast that it is preceding the transform state.
607  rclcpp::Duration shape_transform_cache_lookup_wait_time_;
608 
610  // If state_update_pending_ is true, call updateSceneWithCurrentState()
611  // Not safe to access from callback functions.
612  rclcpp::TimerBase::SharedPtr state_update_timer_;
613 
614  robot_model_loader::RobotModelLoaderPtr rm_loader_;
615  moveit::core::RobotModelConstPtr robot_model_;
616 
618 
619  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr callback_handler_;
620 
621  bool use_sim_time_;
622 
623  friend class LockedPlanningSceneRO;
624  friend class LockedPlanningSceneRW;
625 };
626 
649 {
650 public:
651  LockedPlanningSceneRO(const PlanningSceneMonitorPtr& planning_scene_monitor)
653  {
654  initialize(true);
655  }
656 
657  const PlanningSceneMonitorPtr& getPlanningSceneMonitor()
658  {
660  }
661 
662  operator bool() const
663  {
664  return planning_scene_monitor_ && planning_scene_monitor_->getPlanningScene();
665  }
666 
667  operator const planning_scene::PlanningSceneConstPtr&() const
668  {
669  return static_cast<const PlanningSceneMonitor*>(planning_scene_monitor_.get())->getPlanningScene();
670  }
671 
672  const planning_scene::PlanningSceneConstPtr& operator->() const
673  {
674  return static_cast<const PlanningSceneMonitor*>(planning_scene_monitor_.get())->getPlanningScene();
675  }
676 
677 protected:
678  LockedPlanningSceneRO(const PlanningSceneMonitorPtr& planning_scene_monitor, bool read_only)
680  {
681  initialize(read_only);
682  }
683 
684  void initialize(bool read_only)
685  {
687  lock_ = std::make_shared<SingleUnlock>(planning_scene_monitor_.get(), read_only);
688  }
689 
691 
692  // we use this struct so that lock/unlock are called only once
693  // even if the LockedPlanningScene instance is copied around
695  {
698  {
699  if (read_only)
701  else
703  }
705  {
706  if (read_only_)
708  else
710  }
713  };
714 
715  PlanningSceneMonitorPtr planning_scene_monitor_;
716  SingleUnlockPtr lock_;
717 };
718 
741 {
742 public:
743  LockedPlanningSceneRW(const PlanningSceneMonitorPtr& planning_scene_monitor)
745  {
746  }
747 
748  operator const planning_scene::PlanningScenePtr&()
749  {
750  return planning_scene_monitor_->getPlanningScene();
751  }
752 
753  const planning_scene::PlanningScenePtr& operator->()
754  {
755  return planning_scene_monitor_->getPlanningScene();
756  }
757 };
758 } // namespace planning_scene_monitor
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Definition: world.h:265
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:58
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
const planning_scene::PlanningSceneConstPtr & operator->() const
LockedPlanningSceneRO(const PlanningSceneMonitorPtr &planning_scene_monitor, bool read_only)
LockedPlanningSceneRO(const PlanningSceneMonitorPtr &planning_scene_monitor)
const PlanningSceneMonitorPtr & getPlanningSceneMonitor()
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
const planning_scene::PlanningScenePtr & operator->()
LockedPlanningSceneRW(const PlanningSceneMonitorPtr &planning_scene_monitor)
PlanningSceneMonitor Subscribes to the topic planning_scene.
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.
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
void lockSceneRead()
Lock the scene for reading (multiple threads can lock for reading at the same time)
void lockSceneWrite()
Lock the scene for writing (only one thread can lock for writing and no other thread can lock for rea...
void unlockSceneRead()
Unlock the scene from reading (multiple threads can lock for reading at the same time)
static const std::string DEFAULT_PLANNING_SCENE_SERVICE
The name of the service used by default for requesting full planning scene state.
double default_attached_padd_
default attached padding
std::unique_ptr< occupancy_map_monitor::OccupancyMapMonitor > octomap_monitor_
PlanningSceneMonitor(const rclcpp::Node::SharedPtr &node, const std::string &robot_description, const std::shared_ptr< tf2_ros::Buffer > &, const std::string &name="")
Constructor.
const moveit::core::RobotModelConstPtr & getRobotModel() const
const std::string & getRobotDescription() const
Get the stored robot description.
std::map< std::string, double > default_robot_link_padd_
default robot link padding
static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
The name of the topic used by default for attached collision objects.
PlanningSceneMonitor & operator=(const PlanningSceneMonitor &)=delete
PlanningSceneMonitor cannot be copy-assigned.
static const std::string DEFAULT_COLLISION_OBJECT_TOPIC
The name of the topic used by default for receiving collision objects in the world.
PlanningSceneMonitor(const PlanningSceneMonitor &)=delete
PlanningSceneMonitor cannot be copy-constructed.
rclcpp::Subscription< moveit_msgs::msg::AttachedCollisionObject >::SharedPtr attached_collision_object_subscriber_
std::map< std::string, std::vector< std::pair< occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d * > > > CollisionBodyShapeHandles
const std::string & getName() const
Get the name of this monitor.
rclcpp::Service< moveit_msgs::srv::GetPlanningScene >::SharedPtr get_scene_service_
std::map< const moveit::core::LinkModel *, std::vector< std::pair< occupancy_map_monitor::ShapeHandle, std::size_t > > > LinkShapeHandles
double getDefaultAttachedObjectPadding() const
Get the default attached padding.
planning_scene::PlanningSceneConstPtr scene_const_
const std::shared_ptr< tf2_ros::Buffer > & getTFClient() const
Get the instance of the TF client that was passed to the constructor of this class.
rclcpp::Subscription< moveit_msgs::msg::CollisionObject >::SharedPtr collision_object_subscriber_
rclcpp::Subscription< moveit_msgs::msg::PlanningScene >::SharedPtr planning_scene_subscriber_
PlanningSceneMonitor(const rclcpp::Node::SharedPtr &node, const robot_model_loader::RobotModelLoaderPtr &rml, const std::shared_ptr< tf2_ros::Buffer > &, const std::string &name="")
Constructor.
double getDefaultRobotPadding() const
Get the default robot padding.
std::shared_mutex scene_update_mutex_
if diffs are monitored, this is the pointer to the parent scene
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
double getStateUpdateFrequency() const
Get the maximum frequency (Hz) at which the current state of the planning scene is updated.
std::shared_ptr< rclcpp::executors::SingleThreadedExecutor > private_executor_
const CurrentStateMonitorPtr & getStateMonitor() const
Get the stored instance of the stored current state monitor.
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Avoid this function! Returns an unsafe pointer to the current planning scene.
std::map< const moveit::core::AttachedBody *, std::vector< std::pair< occupancy_map_monitor::ShapeHandle, std::size_t > > > AttachedBodyShapeHandles
double getDefaultObjectPadding() const
Get the default object padding.
std::map< std::string, double > default_robot_link_scale_
default robot link scale
rclcpp::Time last_robot_motion_time_
Last time the state was updated.
double getDefaultRobotScale() const
Get the default robot scaling.
const rclcpp::Time & getLastUpdateTime() const
Return the time when the last update was made to the planning scene (by any monitor)
std::string monitor_name_
The name of this scene monitor.
PlanningSceneMonitor(const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningScenePtr &scene, const std::string &robot_description, const std::shared_ptr< tf2_ros::Buffer > &, const std::string &name="")
Constructor.
std::recursive_mutex update_lock_
lock access to update_callbacks_
rclcpp::Time last_update_time_
mutex for stored scene
PlanningSceneMonitor(const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningScenePtr &scene, const robot_model_loader::RobotModelLoaderPtr &rml, const std::shared_ptr< tf2_ros::Buffer > &, const std::string &name="")
Constructor.
std::unique_ptr< std::thread > publish_planning_scene_
std::shared_ptr< rclcpp::Node > node_
Last time the robot has moved.
rclcpp::Publisher< moveit_msgs::msg::PlanningScene >::SharedPtr planning_scene_publisher_
static const std::string DEFAULT_JOINT_STATES_TOPIC
The name of the topic used by default for receiving joint states.
std::vector< std::function< void(SceneUpdateType)> > update_callbacks_
double getPlanningScenePublishingFrequency() const
Get the maximum frequency at which planning scenes are published (Hz)
planning_scene::PlanningScenePtr parent_scene_
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
void unlockSceneWrite()
Lock the scene from writing (only one thread can lock for writing and no other thread can lock for re...
rclcpp::Subscription< moveit_msgs::msg::PlanningSceneWorld >::SharedPtr planning_scene_world_subscriber_
const robot_model_loader::RobotModelLoaderPtr & getRobotModelLoader() const
Get the user kinematic model loader.
std::map< ShapeHandle, Eigen::Isometry3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Isometry3d > > > ShapeTransformCache
scene
Definition: pick.py:52
MOVEIT_CLASS_FORWARD(PlanningSceneMonitor)
name
Definition: setup.py:7
SingleUnlock(PlanningSceneMonitor *planning_scene_monitor, bool read_only)