moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Types | Public Member Functions | Static Public Attributes | Protected Types | Protected Member Functions | Protected Attributes | Friends | List of all members
planning_scene_monitor::PlanningSceneMonitor Class Reference

PlanningSceneMonitor Subscribes to the topic planning_scene. More...

#include <planning_scene_monitor.h>

Public Types

enum  SceneUpdateType {
  UPDATE_NONE = 0 , UPDATE_STATE = 1 , UPDATE_TRANSFORMS = 2 , UPDATE_GEOMETRY = 4 ,
  UPDATE_SCENE = 8 + UPDATE_STATE + UPDATE_TRANSFORMS + UPDATE_GEOMETRY
}
 

Public Member Functions

 PlanningSceneMonitor (const PlanningSceneMonitor &)=delete
 PlanningSceneMonitor cannot be copy-constructed. More...
 
PlanningSceneMonitoroperator= (const PlanningSceneMonitor &)=delete
 PlanningSceneMonitor cannot be copy-assigned. More...
 
 PlanningSceneMonitor (const rclcpp::Node::SharedPtr &node, const std::string &robot_description, const std::string &name="")
 Constructor. More...
 
 PlanningSceneMonitor (const rclcpp::Node::SharedPtr &node, const robot_model_loader::RobotModelLoaderPtr &rml, const std::string &name="")
 Constructor. More...
 
 PlanningSceneMonitor (const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningScenePtr &scene, const std::string &robot_description, const std::string &name="")
 Constructor. More...
 
 PlanningSceneMonitor (const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningScenePtr &scene, const robot_model_loader::RobotModelLoaderPtr &rml, const std::string &name="")
 Constructor. More...
 
 ~PlanningSceneMonitor ()
 
const std::string & getName () const
 Get the name of this monitor. More...
 
const robot_model_loader::RobotModelLoaderPtr & getRobotModelLoader () const
 Get the user kinematic model loader. More...
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 
const planning_scene::PlanningScenePtr & getPlanningScene ()
 Avoid this function! Returns an unsafe pointer to the current planning scene. More...
 
const planning_scene::PlanningSceneConstPtr & getPlanningScene () const
 Avoid this function! Returns an unsafe pointer to the current planning scene. More...
 
bool updatesScene (const planning_scene::PlanningSceneConstPtr &scene) const
 Return true if the scene scene can be updated directly or indirectly by this monitor. This function will return true if the pointer of the scene is the same as the one maintained, or if a parent of the scene is the one maintained. More...
 
bool updatesScene (const planning_scene::PlanningScenePtr &scene) const
 Return true if the scene scene can be updated directly or indirectly by this monitor. This function will return true if the pointer of the scene is the same as the one maintained, or if a parent of the scene is the one maintained. More...
 
const std::string & getRobotDescription () const
 Get the stored robot description. More...
 
double getDefaultRobotPadding () const
 Get the default robot padding. More...
 
double getDefaultRobotScale () const
 Get the default robot scaling. More...
 
double getDefaultObjectPadding () const
 Get the default object padding. More...
 
double getDefaultAttachedObjectPadding () const
 Get the default attached padding. More...
 
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. More...
 
void monitorDiffs (bool flag)
 By default, the maintained planning scene does not reason about diffs. When the flag passed in is true, the maintained scene starts counting diffs. Future updates to the planning scene will be stored as diffs and can be retrieved as such. Setting the flag to false restores the default behaviour. Maintaining diffs is automatically enabled when publishing planning scenes. More...
 
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 scene. Diffs are sent afterwards on updates specified by the event bitmask. For UPDATE_SCENE, the full scene is always sent. More...
 
void stopPublishingPlanningScene ()
 Stop publishing the maintained planning scene. More...
 
void setPlanningScenePublishingFrequency (double hz)
 Set the maximum frequency at which planning scenes are being published. More...
 
double getPlanningScenePublishingFrequency () const
 Get the maximum frequency at which planning scenes are published (Hz) More...
 
const CurrentStateMonitorPtr & getStateMonitor () const
 Get the stored instance of the stored current state monitor. More...
 
CurrentStateMonitorPtr & getStateMonitorNonConst ()
 
void updateFrameTransforms ()
 Update the transforms for the frames that are not part of the kinematic model using tf. Examples of these frames are the "map" and "odom_combined" transforms. This function is automatically called when data that uses transforms is received. However, this function should also be called before starting a planning request, for example. More...
 
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. More...
 
void stopStateMonitor ()
 Stop the state monitor. More...
 
void updateSceneWithCurrentState ()
 Update the scene using the monitored state. This function is automatically called when an update to the current state is received (if startStateMonitor() has been called). The updates are throttled to a maximum update frequency however, which is set by setStateUpdateFrequency(). More...
 
void setStateUpdateFrequency (double hz)
 Update the scene using the monitored state at a specified frequency, in Hz. This function has an effect only when updates from the CurrentStateMonitor are received at a higher frequency. In that case, the updates are throttled down, so that they do not exceed a maximum update frequency specified here. More...
 
double getStateUpdateFrequency () const
 Get the maximum frequency (Hz) at which the current state of the planning scene is updated. More...
 
void startSceneMonitor (const std::string &scene_topic=DEFAULT_PLANNING_SCENE_TOPIC)
 Start the scene monitor (ROS topic-based) More...
 
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 with providePlanningSceneService(), as it will create a pointless feedback loop. More...
 
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 Rviz PlanningScene display's need for a service without having to use a move_group node. Be careful not to use this in conjunction with requestPlanningSceneState(), as it will create a pointless feedback loop. More...
 
void stopSceneMonitor ()
 Stop the scene monitor. More...
 
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: More...
 
void stopWorldGeometryMonitor ()
 Stop the world geometry monitor. More...
 
void addUpdateCallback (const std::function< void(SceneUpdateType)> &fn)
 Add a function to be called when an update to the scene is received. More...
 
void clearUpdateCallbacks ()
 Clear the functions to be called when an update to the scene is received. More...
 
void getMonitoredTopics (std::vector< std::string > &topics) const
 Get the topic names that the monitor is listening to. More...
 
const rclcpp::Time & getLastUpdateTime () const
 Return the time when the last update was made to the planning scene (by any monitor) More...
 
void publishDebugInformation (bool flag)
 
void triggerSceneUpdateEvent (SceneUpdateType update_type)
 This function is called every time there is a change to the planning scene. More...
 
bool waitForCurrentRobotState (const rclcpp::Time &t, double wait_time=1.)
 Wait for robot state to become more recent than time t. More...
 
void clearOctomap ()
 
bool newPlanningSceneMessage (const moveit_msgs::msg::PlanningScene &scene)
 
bool processCollisionObjectMsg (const moveit_msgs::msg::CollisionObject::ConstSharedPtr &collision_object_msg, const std::optional< moveit_msgs::msg::ObjectColor > &color_msg=std::nullopt)
 
bool processAttachedCollisionObjectMsg (const moveit_msgs::msg::AttachedCollisionObject::ConstSharedPtr &attached_collision_object_msg)
 

Static Public Attributes

static const std::string DEFAULT_JOINT_STATES_TOPIC = "joint_states"
 The name of the topic used by default for receiving joint states. More...
 
static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC = "attached_collision_object"
 The name of the topic used by default for attached collision objects. More...
 
static const std::string DEFAULT_COLLISION_OBJECT_TOPIC = "collision_object"
 The name of the topic used by default for receiving collision objects in the world. More...
 
static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC = "planning_scene_world"
 
static const std::string DEFAULT_PLANNING_SCENE_TOPIC = "planning_scene"
 The name of the topic used by default for receiving full planning scenes or planning scene diffs. More...
 
static const std::string DEFAULT_PLANNING_SCENE_SERVICE = "get_planning_scene"
 The name of the service used by default for requesting full planning scene state. More...
 
static const std::string MONITORED_PLANNING_SCENE_TOPIC = "monitored_planning_scene"
 

Protected Types

typedef std::map< const moveit::core::LinkModel *, std::vector< std::pair< occupancy_map_monitor::ShapeHandle, std::size_t > > > LinkShapeHandles
 
using AttachedBodyShapeHandles = std::map< const moveit::core::AttachedBody *, std::vector< std::pair< occupancy_map_monitor::ShapeHandle, std::size_t > > >
 
using CollisionBodyShapeHandles = std::map< std::string, std::vector< std::pair< occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d * > > >
 

Protected Member Functions

void initialize (const planning_scene::PlanningScenePtr &scene)
 Initialize the planning scene monitor. More...
 
void lockSceneRead ()
 Lock the scene for reading (multiple threads can lock for reading at the same time) More...
 
void unlockSceneRead ()
 Unlock the scene from reading (multiple threads can lock for reading at the same time) More...
 
void lockSceneWrite ()
 Lock the scene for writing (only one thread can lock for writing and no other thread can lock for reading) More...
 
void unlockSceneWrite ()
 Lock the scene from writing (only one thread can lock for writing and no other thread can lock for reading) More...
 
void configureCollisionMatrix (const planning_scene::PlanningScenePtr &scene)
 Configure the collision matrix for a particular scene. More...
 
void configureDefaultPadding ()
 Configure the default padding. More...
 
void newPlanningSceneWorldCallback (const moveit_msgs::msg::PlanningSceneWorld::ConstSharedPtr &world)
 Callback for a new planning scene world. More...
 
void octomapUpdateCallback ()
 Callback for octomap updates. More...
 
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. More...
 
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. More...
 
void includeRobotLinksInOctree ()
 
void excludeRobotLinksFromOctree ()
 
void excludeWorldObjectsFromOctree ()
 
void includeWorldObjectsInOctree ()
 
void excludeWorldObjectFromOctree (const collision_detection::World::ObjectConstPtr &obj)
 
void includeWorldObjectInOctree (const collision_detection::World::ObjectConstPtr &obj)
 
void excludeAttachedBodiesFromOctree ()
 
void includeAttachedBodiesInOctree ()
 
void excludeAttachedBodyFromOctree (const moveit::core::AttachedBody *attached_body)
 
void includeAttachedBodyInOctree (const moveit::core::AttachedBody *attached_body)
 
bool getShapeTransformCache (const std::string &target_frame, const rclcpp::Time &target_time, occupancy_map_monitor::ShapeTransformCache &cache) const
 

Protected Attributes

std::string monitor_name_
 The name of this scene monitor. More...
 
planning_scene::PlanningScenePtr scene_
 
planning_scene::PlanningSceneConstPtr scene_const_
 
planning_scene::PlanningScenePtr parent_scene_
 
std::shared_mutex scene_update_mutex_
 if diffs are monitored, this is the pointer to the parent scene More...
 
rclcpp::Time last_update_time_
 mutex for stored scene More...
 
rclcpp::Time last_robot_motion_time_
 Last time the state was updated. More...
 
std::shared_ptr< rclcpp::Node > node_
 Last time the robot has moved. More...
 
std::shared_ptr< rclcpp::Node > pnode_
 
std::shared_ptr< rclcpp::executors::SingleThreadedExecutor > private_executor_
 
std::thread private_executor_thread_
 
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
 
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
 
std::string robot_description_
 
double default_robot_padd_
 default robot padding More...
 
double default_robot_scale_
 default robot scaling More...
 
double default_object_padd_
 default object padding More...
 
double default_attached_padd_
 default attached padding More...
 
std::map< std::string, double > default_robot_link_padd_
 default robot link padding More...
 
std::map< std::string, double > default_robot_link_scale_
 default robot link scale More...
 
rclcpp::Publisher< moveit_msgs::msg::PlanningScene >::SharedPtr planning_scene_publisher_
 
std::unique_ptr< std::thread > publish_planning_scene_
 
double publish_planning_scene_frequency_
 
SceneUpdateType publish_update_types_
 
std::atomic< SceneUpdateTypenew_scene_update_
 
std::condition_variable_any new_scene_update_condition_
 
rclcpp::Subscription< moveit_msgs::msg::PlanningScene >::SharedPtr planning_scene_subscriber_
 
rclcpp::Subscription< moveit_msgs::msg::PlanningSceneWorld >::SharedPtr planning_scene_world_subscriber_
 
rclcpp::Subscription< moveit_msgs::msg::AttachedCollisionObject >::SharedPtr attached_collision_object_subscriber_
 
rclcpp::Subscription< moveit_msgs::msg::CollisionObject >::SharedPtr collision_object_subscriber_
 
rclcpp::Service< moveit_msgs::srv::GetPlanningScene >::SharedPtr get_scene_service_
 
std::unique_ptr< occupancy_map_monitor::OccupancyMapMonitoroctomap_monitor_
 
CurrentStateMonitorPtr current_state_monitor_
 
LinkShapeHandles link_shape_handles_
 
AttachedBodyShapeHandles attached_body_shape_handles_
 
CollisionBodyShapeHandles collision_body_shape_handles_
 
std::recursive_mutex shape_handles_lock_
 
std::recursive_mutex update_lock_
 lock access to update_callbacks_ More...
 
std::vector< std::function< void(SceneUpdateType)> > update_callbacks_
 

Friends

class LockedPlanningSceneRO
 
class LockedPlanningSceneRW
 

Detailed Description

PlanningSceneMonitor Subscribes to the topic planning_scene.

Definition at line 64 of file planning_scene_monitor.h.

Member Typedef Documentation

◆ AttachedBodyShapeHandles

Definition at line 523 of file planning_scene_monitor.h.

◆ CollisionBodyShapeHandles

using planning_scene_monitor::PlanningSceneMonitor::CollisionBodyShapeHandles = std::map<std::string, std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*> > >
protected

Definition at line 525 of file planning_scene_monitor.h.

◆ LinkShapeHandles

Definition at line 522 of file planning_scene_monitor.h.

Member Enumeration Documentation

◆ SceneUpdateType

Enumerator
UPDATE_NONE 

No update.

UPDATE_STATE 

The state in the monitored scene was updated.

UPDATE_TRANSFORMS 

The maintained set of fixed transforms in the monitored scene was updated.

UPDATE_GEOMETRY 

The geometry of the scene was updated. This includes receiving new octomaps, collision objects, attached objects, scene geometry, etc.

UPDATE_SCENE 

The entire scene was updated.

Definition at line 77 of file planning_scene_monitor.h.

Constructor & Destructor Documentation

◆ PlanningSceneMonitor() [1/5]

planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor ( const PlanningSceneMonitor )
delete

PlanningSceneMonitor cannot be copy-constructed.

◆ PlanningSceneMonitor() [2/5]

planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor ( const rclcpp::Node::SharedPtr &  node,
const std::string &  robot_description,
const std::string &  name = "" 
)

Constructor.

Parameters
robot_descriptionThe name of the ROS parameter that contains the URDF (in string format)
nameA name identifying this planning scene monitor

Definition at line 67 of file planning_scene_monitor.cpp.

◆ PlanningSceneMonitor() [3/5]

planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor ( const rclcpp::Node::SharedPtr &  node,
const robot_model_loader::RobotModelLoaderPtr &  rml,
const std::string &  name = "" 
)

Constructor.

Parameters
rmlA pointer to a kinematic model loader
nameA name identifying this planning scene monitor

Definition at line 81 of file planning_scene_monitor.cpp.

◆ PlanningSceneMonitor() [4/5]

planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor ( const rclcpp::Node::SharedPtr &  node,
const planning_scene::PlanningScenePtr &  scene,
const std::string &  robot_description,
const std::string &  name = "" 
)

Constructor.

Parameters
sceneThe scene instance to maintain up to date with monitored information
robot_descriptionThe name of the ROS parameter that contains the URDF (in string format)
nameA name identifying this planning scene monitor

Definition at line 73 of file planning_scene_monitor.cpp.

◆ PlanningSceneMonitor() [5/5]

planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor ( const rclcpp::Node::SharedPtr &  node,
const planning_scene::PlanningScenePtr &  scene,
const robot_model_loader::RobotModelLoaderPtr &  rml,
const std::string &  name = "" 
)

Constructor.

Parameters
sceneThe scene instance to maintain up to date with monitored information
rmlA pointer to a kinematic model loader
nameA name identifying this planning scene monitor

Definition at line 88 of file planning_scene_monitor.cpp.

Here is the call graph for this function:

◆ ~PlanningSceneMonitor()

planning_scene_monitor::PlanningSceneMonitor::~PlanningSceneMonitor ( )

Definition at line 121 of file planning_scene_monitor.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ addUpdateCallback()

void planning_scene_monitor::PlanningSceneMonitor::addUpdateCallback ( const std::function< void(SceneUpdateType)> &  fn)

Add a function to be called when an update to the scene is received.

Definition at line 1536 of file planning_scene_monitor.cpp.

◆ clearOctomap()

void planning_scene_monitor::PlanningSceneMonitor::clearOctomap ( )

Definition at line 689 of file planning_scene_monitor.cpp.

Here is the call graph for this function:

◆ clearUpdateCallbacks()

void planning_scene_monitor::PlanningSceneMonitor::clearUpdateCallbacks ( )

Clear the functions to be called when an update to the scene is received.

Definition at line 1543 of file planning_scene_monitor.cpp.

◆ configureCollisionMatrix()

void planning_scene_monitor::PlanningSceneMonitor::configureCollisionMatrix ( const planning_scene::PlanningScenePtr &  scene)
protected

Configure the collision matrix for a particular scene.

Definition at line 1605 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ configureDefaultPadding()

void planning_scene_monitor::PlanningSceneMonitor::configureDefaultPadding ( )
protected

Configure the default padding.

Definition at line 1653 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ currentStateAttachedBodyUpdateCallback()

void planning_scene_monitor::PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback ( moveit::core::AttachedBody attached_body,
bool  just_attached 
)
protected

Callback for a change for an attached object of the current state of the planning scene.

Definition at line 1049 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ currentWorldObjectUpdateCallback()

void planning_scene_monitor::PlanningSceneMonitor::currentWorldObjectUpdateCallback ( const collision_detection::World::ObjectConstPtr &  object,
collision_detection::World::Action  action 
)
protected

Callback for a change in the world maintained by the planning scene.

Definition at line 1065 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ excludeAttachedBodiesFromOctree()

void planning_scene_monitor::PlanningSceneMonitor::excludeAttachedBodiesFromOctree ( )
protected

Definition at line 931 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ excludeAttachedBodyFromOctree()

void planning_scene_monitor::PlanningSceneMonitor::excludeAttachedBodyFromOctree ( const moveit::core::AttachedBody attached_body)
protected

Definition at line 970 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ excludeRobotLinksFromOctree()

void planning_scene_monitor::PlanningSceneMonitor::excludeRobotLinksFromOctree ( )
protected

Definition at line 859 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ excludeWorldObjectFromOctree()

void planning_scene_monitor::PlanningSceneMonitor::excludeWorldObjectFromOctree ( const collision_detection::World::ObjectConstPtr &  obj)
protected

Definition at line 1009 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ excludeWorldObjectsFromOctree()

void planning_scene_monitor::PlanningSceneMonitor::excludeWorldObjectsFromOctree ( )
protected

Definition at line 961 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getDefaultAttachedObjectPadding()

double planning_scene_monitor::PlanningSceneMonitor::getDefaultAttachedObjectPadding ( ) const
inline

Get the default attached padding.

Definition at line 233 of file planning_scene_monitor.h.

◆ getDefaultObjectPadding()

double planning_scene_monitor::PlanningSceneMonitor::getDefaultObjectPadding ( ) const
inline

Get the default object padding.

Definition at line 227 of file planning_scene_monitor.h.

◆ getDefaultRobotPadding()

double planning_scene_monitor::PlanningSceneMonitor::getDefaultRobotPadding ( ) const
inline

Get the default robot padding.

Definition at line 215 of file planning_scene_monitor.h.

◆ getDefaultRobotScale()

double planning_scene_monitor::PlanningSceneMonitor::getDefaultRobotScale ( ) const
inline

Get the default robot scaling.

Definition at line 221 of file planning_scene_monitor.h.

◆ getLastUpdateTime()

const rclcpp::Time& planning_scene_monitor::PlanningSceneMonitor::getLastUpdateTime ( ) const
inline

Return the time when the last update was made to the planning scene (by any monitor)

Definition at line 373 of file planning_scene_monitor.h.

◆ getMonitoredTopics()

void planning_scene_monitor::PlanningSceneMonitor::getMonitoredTopics ( std::vector< std::string > &  topics) const

Get the topic names that the monitor is listening to.

Definition at line 530 of file planning_scene_monitor.cpp.

◆ getName()

const std::string& planning_scene_monitor::PlanningSceneMonitor::getName ( ) const
inline

Get the name of this monitor.

Definition at line 152 of file planning_scene_monitor.h.

Here is the caller graph for this function:

◆ getPlanningScene() [1/2]

const planning_scene::PlanningScenePtr& planning_scene_monitor::PlanningSceneMonitor::getPlanningScene ( )
inline

Avoid this function! Returns an unsafe pointer to the current planning scene.

Warning
Most likely you do not want to call this function directly. PlanningSceneMonitor has a background thread which repeatedly updates and clobbers various contents of its internal PlanningScene instance. This function just returns a pointer to that dynamic internal object. The correct thing is usually to use a LockedPlanningSceneRO or LockedPlanningSceneRW, which locks the PlanningSceneMonitor and provides safe access to the PlanningScene object.
See also
LockedPlanningSceneRO
LockedPlanningSceneRW.
Returns
A pointer to the current planning scene.

Definition at line 182 of file planning_scene_monitor.h.

Here is the caller graph for this function:

◆ getPlanningScene() [2/2]

const planning_scene::PlanningSceneConstPtr& planning_scene_monitor::PlanningSceneMonitor::getPlanningScene ( ) const
inline

Avoid this function! Returns an unsafe pointer to the current planning scene.

Warning
Most likely you do not want to call this function directly. PlanningSceneMonitor has a background thread which repeatedly updates and clobbers various contents of its internal PlanningScene instance. This function just returns a pointer to that dynamic internal object. The correct thing is usually to use a LockedPlanningSceneRO or LockedPlanningSceneRW, which locks the PlanningSceneMonitor and provides safe access to the PlanningScene object.
See also
LockedPlanningSceneRO
LockedPlanningSceneRW.
Returns
A pointer to the current planning scene.

Definition at line 190 of file planning_scene_monitor.h.

◆ getPlanningScenePublishingFrequency()

double planning_scene_monitor::PlanningSceneMonitor::getPlanningScenePublishingFrequency ( ) const
inline

Get the maximum frequency at which planning scenes are published (Hz)

Definition at line 264 of file planning_scene_monitor.h.

◆ getRobotDescription()

const std::string& planning_scene_monitor::PlanningSceneMonitor::getRobotDescription ( ) const
inline

Get the stored robot description.

Returns
An instance of the stored robot description

Definition at line 209 of file planning_scene_monitor.h.

◆ getRobotModel()

const moveit::core::RobotModelConstPtr& planning_scene_monitor::PlanningSceneMonitor::getRobotModel ( ) const
inline

Definition at line 163 of file planning_scene_monitor.h.

Here is the caller graph for this function:

◆ getRobotModelLoader()

const robot_model_loader::RobotModelLoaderPtr& planning_scene_monitor::PlanningSceneMonitor::getRobotModelLoader ( ) const
inline

Get the user kinematic model loader.

Definition at line 158 of file planning_scene_monitor.h.

◆ getShapeTransformCache()

bool planning_scene_monitor::PlanningSceneMonitor::getShapeTransformCache ( const std::string &  target_frame,
const rclcpp::Time &  target_time,
occupancy_map_monitor::ShapeTransformCache cache 
) const
protected

Definition at line 1199 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ getStateMonitor()

const CurrentStateMonitorPtr& planning_scene_monitor::PlanningSceneMonitor::getStateMonitor ( ) const
inline

Get the stored instance of the stored current state monitor.

Returns
An instance of the stored current state monitor

Definition at line 271 of file planning_scene_monitor.h.

◆ getStateMonitorNonConst()

CurrentStateMonitorPtr& planning_scene_monitor::PlanningSceneMonitor::getStateMonitorNonConst ( )
inline

Definition at line 276 of file planning_scene_monitor.h.

◆ getStateUpdateFrequency()

double planning_scene_monitor::PlanningSceneMonitor::getStateUpdateFrequency ( ) const
inline

Get the maximum frequency (Hz) at which the current state of the planning scene is updated.

Definition at line 310 of file planning_scene_monitor.h.

◆ getTFClient()

const std::shared_ptr<tf2_ros::Buffer>& planning_scene_monitor::PlanningSceneMonitor::getTFClient ( ) const
inline

Get the instance of the TF client that was passed to the constructor of this class.

Definition at line 239 of file planning_scene_monitor.h.

◆ includeAttachedBodiesInOctree()

void planning_scene_monitor::PlanningSceneMonitor::includeAttachedBodiesInOctree ( )
protected

Definition at line 913 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ includeAttachedBodyInOctree()

void planning_scene_monitor::PlanningSceneMonitor::includeAttachedBodyInOctree ( const moveit::core::AttachedBody attached_body)
protected

Definition at line 992 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ includeRobotLinksInOctree()

void planning_scene_monitor::PlanningSceneMonitor::includeRobotLinksInOctree ( )
protected

Definition at line 896 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ includeWorldObjectInOctree()

void planning_scene_monitor::PlanningSceneMonitor::includeWorldObjectInOctree ( const collision_detection::World::ObjectConstPtr &  obj)
protected

Definition at line 1032 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ includeWorldObjectsInOctree()

void planning_scene_monitor::PlanningSceneMonitor::includeWorldObjectsInOctree ( )
protected

Definition at line 943 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ initialize()

void planning_scene_monitor::PlanningSceneMonitor::initialize ( const planning_scene::PlanningScenePtr &  scene)
protected

Initialize the planning scene monitor.

Parameters
sceneThe scene instance to fill with data (an instance is allocated if the one passed in is not allocated)

Definition at line 146 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ lockSceneRead()

void planning_scene_monitor::PlanningSceneMonitor::lockSceneRead ( )
protected

Lock the scene for reading (multiple threads can lock for reading at the same time)

Definition at line 1146 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ lockSceneWrite()

void planning_scene_monitor::PlanningSceneMonitor::lockSceneWrite ( )
protected

Lock the scene for writing (only one thread can lock for writing and no other thread can lock for reading)

Definition at line 1160 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ monitorDiffs()

void planning_scene_monitor::PlanningSceneMonitor::monitorDiffs ( bool  flag)

By default, the maintained planning scene does not reason about diffs. When the flag passed in is true, the maintained scene starts counting diffs. Future updates to the planning scene will be stored as diffs and can be retrieved as such. Setting the flag to false restores the default behaviour. Maintaining diffs is automatically enabled when publishing planning scenes.

Definition at line 352 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ newPlanningSceneMessage()

bool planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneMessage ( const moveit_msgs::msg::PlanningScene &  scene)

Definition at line 712 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ newPlanningSceneWorldCallback()

void planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneWorldCallback ( const moveit_msgs::msg::PlanningSceneWorld::ConstSharedPtr &  world)
protected

Callback for a new planning scene world.

Definition at line 834 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ octomapUpdateCallback()

void planning_scene_monitor::PlanningSceneMonitor::octomapUpdateCallback ( )
protected

Callback for octomap updates.

Definition at line 1446 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ operator=()

PlanningSceneMonitor& planning_scene_monitor::PlanningSceneMonitor::operator= ( const PlanningSceneMonitor )
delete

PlanningSceneMonitor cannot be copy-assigned.

◆ processAttachedCollisionObjectMsg()

bool planning_scene_monitor::PlanningSceneMonitor::processAttachedCollisionObjectMsg ( const moveit_msgs::msg::AttachedCollisionObject::ConstSharedPtr &  attached_collision_object_msg)

Definition at line 814 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ processCollisionObjectMsg()

bool planning_scene_monitor::PlanningSceneMonitor::processCollisionObjectMsg ( const moveit_msgs::msg::CollisionObject::ConstSharedPtr &  collision_object_msg,
const std::optional< moveit_msgs::msg::ObjectColor > &  color_msg = std::nullopt 
)

Definition at line 794 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ providePlanningSceneService()

void planning_scene_monitor::PlanningSceneMonitor::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 Rviz PlanningScene display's need for a service without having to use a move_group node. Be careful not to use this in conjunction with requestPlanningSceneState(), as it will create a pointless feedback loop.

Parameters
service_nameThe topic to provide the service

Definition at line 631 of file planning_scene_monitor.cpp.

◆ publishDebugInformation()

void planning_scene_monitor::PlanningSceneMonitor::publishDebugInformation ( bool  flag)

Definition at line 1599 of file planning_scene_monitor.cpp.

◆ requestPlanningSceneState()

bool planning_scene_monitor::PlanningSceneMonitor::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 with providePlanningSceneService(), as it will create a pointless feedback loop.

Parameters
service_nameThe name of the service to use for requesting the planning scene. This must be a service of type moveit_msgs::srv::GetPlanningScene and is usually called "/get_planning_scene".

Definition at line 586 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setPlanningScenePublishingFrequency()

void planning_scene_monitor::PlanningSceneMonitor::setPlanningScenePublishingFrequency ( double  hz)

Set the maximum frequency at which planning scenes are being published.

Definition at line 1549 of file planning_scene_monitor.cpp.

◆ setStateUpdateFrequency()

void planning_scene_monitor::PlanningSceneMonitor::setStateUpdateFrequency ( double  hz)

Update the scene using the monitored state at a specified frequency, in Hz. This function has an effect only when updates from the CurrentStateMonitor are received at a higher frequency. In that case, the updates are throttled down, so that they do not exceed a maximum update frequency specified here.

Parameters
hzthe update frequency. By default this is 10Hz.

Definition at line 1470 of file planning_scene_monitor.cpp.

Here is the call graph for this function:

◆ startPublishingPlanningScene()

void planning_scene_monitor::PlanningSceneMonitor::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 scene. Diffs are sent afterwards on updates specified by the event bitmask. For UPDATE_SCENE, the full scene is always sent.

Definition at line 415 of file planning_scene_monitor.cpp.

Here is the call graph for this function:

◆ startSceneMonitor()

void planning_scene_monitor::PlanningSceneMonitor::startSceneMonitor ( const std::string &  scene_topic = DEFAULT_PLANNING_SCENE_TOPIC)

Start the scene monitor (ROS topic-based)

Parameters
scene_topicThe name of the planning scene topic

Definition at line 1174 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ startStateMonitor()

void planning_scene_monitor::PlanningSceneMonitor::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.

Parameters
joint_states_topicthe topic to listen to for joint states
attached_objects_topicthe topic to listen to for attached collision objects

Definition at line 1332 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ startWorldGeometryMonitor()

void planning_scene_monitor::PlanningSceneMonitor::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:

  • Requests to add/remove/update collision objects to/from the world
  • The collision map
  • Requests to attached/detach collision objects
    Parameters
    collision_objects_topicThe topic on which to listen for collision objects
    planning_scene_world_topicThe topic to listen to for world scene geometry
    load_octomap_monitorFlag to disable octomap monitor if desired

Definition at line 1268 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ stopPublishingPlanningScene()

void planning_scene_monitor::PlanningSceneMonitor::stopPublishingPlanningScene ( )

Stop publishing the maintained planning scene.

Definition at line 401 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ stopSceneMonitor()

void planning_scene_monitor::PlanningSceneMonitor::stopSceneMonitor ( )

Stop the scene monitor.

Definition at line 1190 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ stopStateMonitor()

void planning_scene_monitor::PlanningSceneMonitor::stopStateMonitor ( )

Stop the state monitor.

Definition at line 1374 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ stopWorldGeometryMonitor()

void planning_scene_monitor::PlanningSceneMonitor::stopWorldGeometryMonitor ( )

Stop the world geometry monitor.

Definition at line 1316 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ triggerSceneUpdateEvent()

void planning_scene_monitor::PlanningSceneMonitor::triggerSceneUpdateEvent ( SceneUpdateType  update_type)

This function is called every time there is a change to the planning scene.

Definition at line 575 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ unlockSceneRead()

void planning_scene_monitor::PlanningSceneMonitor::unlockSceneRead ( )
protected

Unlock the scene from reading (multiple threads can lock for reading at the same time)

Definition at line 1153 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ unlockSceneWrite()

void planning_scene_monitor::PlanningSceneMonitor::unlockSceneWrite ( )
protected

Lock the scene from writing (only one thread can lock for writing and no other thread can lock for reading)

Definition at line 1167 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ updateFrameTransforms()

void planning_scene_monitor::PlanningSceneMonitor::updateFrameTransforms ( )

Update the transforms for the frames that are not part of the kinematic model using tf. Examples of these frames are the "map" and "odom_combined" transforms. This function is automatically called when data that uses transforms is received. However, this function should also be called before starting a planning request, for example.

Definition at line 1584 of file planning_scene_monitor.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateSceneWithCurrentState()

void planning_scene_monitor::PlanningSceneMonitor::updateSceneWithCurrentState ( )

Update the scene using the monitored state. This function is automatically called when an update to the current state is received (if startStateMonitor() has been called). The updates are throttled to a maximum update frequency however, which is set by setStateUpdateFrequency().

Definition at line 1499 of file planning_scene_monitor.cpp.

Here is the caller graph for this function:

◆ updatesScene() [1/2]

bool planning_scene_monitor::PlanningSceneMonitor::updatesScene ( const planning_scene::PlanningSceneConstPtr &  scene) const

Return true if the scene scene can be updated directly or indirectly by this monitor. This function will return true if the pointer of the scene is the same as the one maintained, or if a parent of the scene is the one maintained.

Definition at line 570 of file planning_scene_monitor.cpp.

◆ updatesScene() [2/2]

bool planning_scene_monitor::PlanningSceneMonitor::updatesScene ( const planning_scene::PlanningScenePtr &  scene) const

Return true if the scene scene can be updated directly or indirectly by this monitor. This function will return true if the pointer of the scene is the same as the one maintained, or if a parent of the scene is the one maintained.

Definition at line 565 of file planning_scene_monitor.cpp.

◆ waitForCurrentRobotState()

bool planning_scene_monitor::PlanningSceneMonitor::waitForCurrentRobotState ( const rclcpp::Time &  t,
double  wait_time = 1. 
)

Wait for robot state to become more recent than time t.

If there is no state monitor active, there will be no scene updates. Hence, you can specify a timeout to wait for those updates. Default is 1s.

Definition at line 1088 of file planning_scene_monitor.cpp.

Here is the call graph for this function:

Friends And Related Function Documentation

◆ LockedPlanningSceneRO

friend class LockedPlanningSceneRO
friend

Definition at line 595 of file planning_scene_monitor.h.

◆ LockedPlanningSceneRW

friend class LockedPlanningSceneRW
friend

Definition at line 596 of file planning_scene_monitor.h.

Member Data Documentation

◆ attached_body_shape_handles_

AttachedBodyShapeHandles planning_scene_monitor::PlanningSceneMonitor::attached_body_shape_handles_
protected

Definition at line 529 of file planning_scene_monitor.h.

◆ attached_collision_object_subscriber_

rclcpp::Subscription<moveit_msgs::msg::AttachedCollisionObject>::SharedPtr planning_scene_monitor::PlanningSceneMonitor::attached_collision_object_subscriber_
protected

Definition at line 507 of file planning_scene_monitor.h.

◆ collision_body_shape_handles_

CollisionBodyShapeHandles planning_scene_monitor::PlanningSceneMonitor::collision_body_shape_handles_
protected

Definition at line 530 of file planning_scene_monitor.h.

◆ collision_object_subscriber_

rclcpp::Subscription<moveit_msgs::msg::CollisionObject>::SharedPtr planning_scene_monitor::PlanningSceneMonitor::collision_object_subscriber_
protected

Definition at line 508 of file planning_scene_monitor.h.

◆ current_state_monitor_

CurrentStateMonitorPtr planning_scene_monitor::PlanningSceneMonitor::current_state_monitor_
protected

Definition at line 518 of file planning_scene_monitor.h.

◆ DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC

const std::string planning_scene_monitor::PlanningSceneMonitor::DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC = "attached_collision_object"
static

The name of the topic used by default for attached collision objects.

Definition at line 100 of file planning_scene_monitor.h.

◆ default_attached_padd_

double planning_scene_monitor::PlanningSceneMonitor::default_attached_padd_
protected

default attached padding

Definition at line 489 of file planning_scene_monitor.h.

◆ DEFAULT_COLLISION_OBJECT_TOPIC

const std::string planning_scene_monitor::PlanningSceneMonitor::DEFAULT_COLLISION_OBJECT_TOPIC = "collision_object"
static

The name of the topic used by default for receiving collision objects in the world.

Definition at line 103 of file planning_scene_monitor.h.

◆ DEFAULT_JOINT_STATES_TOPIC

const std::string planning_scene_monitor::PlanningSceneMonitor::DEFAULT_JOINT_STATES_TOPIC = "joint_states"
static

The name of the topic used by default for receiving joint states.

Definition at line 97 of file planning_scene_monitor.h.

◆ default_object_padd_

double planning_scene_monitor::PlanningSceneMonitor::default_object_padd_
protected

default object padding

Definition at line 487 of file planning_scene_monitor.h.

◆ DEFAULT_PLANNING_SCENE_SERVICE

const std::string planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_SERVICE = "get_planning_scene"
static

The name of the service used by default for requesting full planning scene state.

Definition at line 113 of file planning_scene_monitor.h.

◆ DEFAULT_PLANNING_SCENE_TOPIC

const std::string planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_TOPIC = "planning_scene"
static

The name of the topic used by default for receiving full planning scenes or planning scene diffs.

Definition at line 110 of file planning_scene_monitor.h.

◆ DEFAULT_PLANNING_SCENE_WORLD_TOPIC

const std::string planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_WORLD_TOPIC = "planning_scene_world"
static

The name of the topic used by default for receiving geometry information about a planning scene (complete overwrite of world geometry)

Definition at line 107 of file planning_scene_monitor.h.

◆ default_robot_link_padd_

std::map<std::string, double> planning_scene_monitor::PlanningSceneMonitor::default_robot_link_padd_
protected

default robot link padding

Definition at line 491 of file planning_scene_monitor.h.

◆ default_robot_link_scale_

std::map<std::string, double> planning_scene_monitor::PlanningSceneMonitor::default_robot_link_scale_
protected

default robot link scale

Definition at line 493 of file planning_scene_monitor.h.

◆ default_robot_padd_

double planning_scene_monitor::PlanningSceneMonitor::default_robot_padd_
protected

default robot padding

Definition at line 483 of file planning_scene_monitor.h.

◆ default_robot_scale_

double planning_scene_monitor::PlanningSceneMonitor::default_robot_scale_
protected

default robot scaling

Definition at line 485 of file planning_scene_monitor.h.

◆ get_scene_service_

rclcpp::Service<moveit_msgs::srv::GetPlanningScene>::SharedPtr planning_scene_monitor::PlanningSceneMonitor::get_scene_service_
protected

Definition at line 512 of file planning_scene_monitor.h.

◆ last_robot_motion_time_

rclcpp::Time planning_scene_monitor::PlanningSceneMonitor::last_robot_motion_time_
protected

Last time the state was updated.

Definition at line 466 of file planning_scene_monitor.h.

◆ last_update_time_

rclcpp::Time planning_scene_monitor::PlanningSceneMonitor::last_update_time_
protected

mutex for stored scene

Definition at line 465 of file planning_scene_monitor.h.

◆ link_shape_handles_

LinkShapeHandles planning_scene_monitor::PlanningSceneMonitor::link_shape_handles_
protected

Definition at line 528 of file planning_scene_monitor.h.

◆ monitor_name_

std::string planning_scene_monitor::PlanningSceneMonitor::monitor_name_
protected

The name of this scene monitor.

Definition at line 459 of file planning_scene_monitor.h.

◆ MONITORED_PLANNING_SCENE_TOPIC

const std::string planning_scene_monitor::PlanningSceneMonitor::MONITORED_PLANNING_SCENE_TOPIC = "monitored_planning_scene"
static

The name of the topic used by default for publishing the monitored planning scene (this is without "/" in the name, so the topic is prefixed by the node name)

Definition at line 117 of file planning_scene_monitor.h.

◆ new_scene_update_

std::atomic<SceneUpdateType> planning_scene_monitor::PlanningSceneMonitor::new_scene_update_
protected

Definition at line 500 of file planning_scene_monitor.h.

◆ new_scene_update_condition_

std::condition_variable_any planning_scene_monitor::PlanningSceneMonitor::new_scene_update_condition_
protected

Definition at line 501 of file planning_scene_monitor.h.

◆ node_

std::shared_ptr<rclcpp::Node> planning_scene_monitor::PlanningSceneMonitor::node_
protected

Last time the robot has moved.

Definition at line 468 of file planning_scene_monitor.h.

◆ octomap_monitor_

std::unique_ptr<occupancy_map_monitor::OccupancyMapMonitor> planning_scene_monitor::PlanningSceneMonitor::octomap_monitor_
protected

Definition at line 515 of file planning_scene_monitor.h.

◆ parent_scene_

planning_scene::PlanningScenePtr planning_scene_monitor::PlanningSceneMonitor::parent_scene_
protected

Definition at line 463 of file planning_scene_monitor.h.

◆ planning_scene_publisher_

rclcpp::Publisher<moveit_msgs::msg::PlanningScene>::SharedPtr planning_scene_monitor::PlanningSceneMonitor::planning_scene_publisher_
protected

Definition at line 496 of file planning_scene_monitor.h.

◆ planning_scene_subscriber_

rclcpp::Subscription<moveit_msgs::msg::PlanningScene>::SharedPtr planning_scene_monitor::PlanningSceneMonitor::planning_scene_subscriber_
protected

Definition at line 504 of file planning_scene_monitor.h.

◆ planning_scene_world_subscriber_

rclcpp::Subscription<moveit_msgs::msg::PlanningSceneWorld>::SharedPtr planning_scene_monitor::PlanningSceneMonitor::planning_scene_world_subscriber_
protected

Definition at line 505 of file planning_scene_monitor.h.

◆ pnode_

std::shared_ptr<rclcpp::Node> planning_scene_monitor::PlanningSceneMonitor::pnode_
protected

Definition at line 473 of file planning_scene_monitor.h.

◆ private_executor_

std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> planning_scene_monitor::PlanningSceneMonitor::private_executor_
protected

Definition at line 474 of file planning_scene_monitor.h.

◆ private_executor_thread_

std::thread planning_scene_monitor::PlanningSceneMonitor::private_executor_thread_
protected

Definition at line 475 of file planning_scene_monitor.h.

◆ publish_planning_scene_

std::unique_ptr<std::thread> planning_scene_monitor::PlanningSceneMonitor::publish_planning_scene_
protected

Definition at line 497 of file planning_scene_monitor.h.

◆ publish_planning_scene_frequency_

double planning_scene_monitor::PlanningSceneMonitor::publish_planning_scene_frequency_
protected

Definition at line 498 of file planning_scene_monitor.h.

◆ publish_update_types_

SceneUpdateType planning_scene_monitor::PlanningSceneMonitor::publish_update_types_
protected

Definition at line 499 of file planning_scene_monitor.h.

◆ robot_description_

std::string planning_scene_monitor::PlanningSceneMonitor::robot_description_
protected

Definition at line 480 of file planning_scene_monitor.h.

◆ scene_

planning_scene::PlanningScenePtr planning_scene_monitor::PlanningSceneMonitor::scene_
protected

Definition at line 461 of file planning_scene_monitor.h.

◆ scene_const_

planning_scene::PlanningSceneConstPtr planning_scene_monitor::PlanningSceneMonitor::scene_const_
protected

Definition at line 462 of file planning_scene_monitor.h.

◆ scene_update_mutex_

std::shared_mutex planning_scene_monitor::PlanningSceneMonitor::scene_update_mutex_
protected

if diffs are monitored, this is the pointer to the parent scene

Definition at line 464 of file planning_scene_monitor.h.

◆ shape_handles_lock_

std::recursive_mutex planning_scene_monitor::PlanningSceneMonitor::shape_handles_lock_
mutableprotected

Definition at line 531 of file planning_scene_monitor.h.

◆ tf_buffer_

std::shared_ptr<tf2_ros::Buffer> planning_scene_monitor::PlanningSceneMonitor::tf_buffer_
protected

Definition at line 477 of file planning_scene_monitor.h.

◆ tf_listener_

std::shared_ptr<tf2_ros::TransformListener> planning_scene_monitor::PlanningSceneMonitor::tf_listener_
protected

Definition at line 478 of file planning_scene_monitor.h.

◆ update_callbacks_

std::vector<std::function<void(SceneUpdateType)> > planning_scene_monitor::PlanningSceneMonitor::update_callbacks_
protected

Definition at line 535 of file planning_scene_monitor.h.

◆ update_lock_

std::recursive_mutex planning_scene_monitor::PlanningSceneMonitor::update_lock_
protected

lock access to update_callbacks_

Definition at line 534 of file planning_scene_monitor.h.


The documentation for this class was generated from the following files: