moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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... | |
PlanningSceneMonitor & | operator= (const PlanningSceneMonitor &)=delete |
PlanningSceneMonitor cannot be copy-assigned. More... | |
PlanningSceneMonitor (const rclcpp::Node::SharedPtr &node, const std::string &robot_description, const std::shared_ptr< tf2_ros::Buffer > &, const std::string &name="") | |
Constructor. More... | |
PlanningSceneMonitor (const rclcpp::Node::SharedPtr &node, const std::string &robot_description, const std::string &name="") | |
PlanningSceneMonitor (const rclcpp::Node::SharedPtr &node, const robot_model_loader::RobotModelLoaderPtr &rml, const std::shared_ptr< tf2_ros::Buffer > &, const std::string &name="") | |
Constructor. More... | |
PlanningSceneMonitor (const rclcpp::Node::SharedPtr &node, const robot_model_loader::RobotModelLoaderPtr &rml, const std::string &name="") | |
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. More... | |
PlanningSceneMonitor (const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningScenePtr &scene, const std::string &robot_description, const std::string &name="") | |
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. More... | |
PlanningSceneMonitor (const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningScenePtr &scene, const robot_model_loader::RobotModelLoaderPtr &rml, const std::string &name="") | |
~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) |
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 | collisionObjectCallback (const moveit_msgs::msg::CollisionObject::ConstSharedPtr &obj) |
Callback for a new collision object msg. 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 | attachObjectCallback (const moveit_msgs::msg::AttachedCollisionObject::ConstSharedPtr &obj) |
Callback for a new attached object msg. 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< SceneUpdateType > | new_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::OccupancyMapMonitor > | octomap_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 |
PlanningSceneMonitor Subscribes to the topic planning_scene.
Definition at line 64 of file planning_scene_monitor.h.
|
protected |
Definition at line 547 of file planning_scene_monitor.h.
|
protected |
Definition at line 549 of file planning_scene_monitor.h.
|
protected |
Definition at line 546 of file planning_scene_monitor.h.
Definition at line 77 of file planning_scene_monitor.h.
|
delete |
PlanningSceneMonitor cannot be copy-constructed.
|
inline |
Constructor.
robot_description | The name of the ROS parameter that contains the URDF (in string format) |
tf_buffer | A pointer to a tf2_ros::Buffer |
name | A name identifying this planning scene monitor |
Definition at line 124 of file planning_scene_monitor.h.
planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor | ( | const rclcpp::Node::SharedPtr & | node, |
const std::string & | robot_description, | ||
const std::string & | name = "" |
||
) |
Definition at line 68 of file planning_scene_monitor.cpp.
|
inline |
Constructor.
rml | A pointer to a kinematic model loader |
tf_buffer | A pointer to a tf2_ros::Buffer |
name | A name identifying this planning scene monitor |
Definition at line 138 of file planning_scene_monitor.h.
planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor | ( | const rclcpp::Node::SharedPtr & | node, |
const robot_model_loader::RobotModelLoaderPtr & | rml, | ||
const std::string & | name = "" |
||
) |
Definition at line 82 of file planning_scene_monitor.cpp.
|
inline |
Constructor.
scene | The scene instance to maintain up to date with monitored information |
robot_description | The name of the ROS parameter that contains the URDF (in string format) |
tf_buffer | A pointer to a tf2_ros::Buffer |
name | A name identifying this planning scene monitor |
Definition at line 153 of file planning_scene_monitor.h.
planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor | ( | const rclcpp::Node::SharedPtr & | node, |
const planning_scene::PlanningScenePtr & | scene, | ||
const std::string & | robot_description, | ||
const std::string & | name = "" |
||
) |
Definition at line 74 of file planning_scene_monitor.cpp.
|
inline |
Constructor.
scene | The scene instance to maintain up to date with monitored information |
rml | A pointer to a kinematic model loader |
tf_buffer | A pointer to a tf2_ros::Buffer |
name | A name identifying this planning scene monitor |
Definition at line 169 of file planning_scene_monitor.h.
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 = "" |
||
) |
planning_scene_monitor::PlanningSceneMonitor::~PlanningSceneMonitor | ( | ) |
Definition at line 121 of file planning_scene_monitor.cpp.
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 1424 of file planning_scene_monitor.cpp.
|
protected |
Callback for a new attached object msg.
Definition at line 769 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::clearOctomap | ( | ) |
Definition at line 627 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::clearUpdateCallbacks | ( | ) |
Clear the functions to be called when an update to the scene is received.
Definition at line 1431 of file planning_scene_monitor.cpp.
|
protected |
Callback for a new collision object msg.
Definition at line 754 of file planning_scene_monitor.cpp.
|
protected |
Configure the collision matrix for a particular scene.
Definition at line 1493 of file planning_scene_monitor.cpp.
|
protected |
Configure the default padding.
Definition at line 1539 of file planning_scene_monitor.cpp.
|
protected |
Callback for a change for an attached object of the current state of the planning scene.
Definition at line 967 of file planning_scene_monitor.cpp.
|
protected |
Callback for a change in the world maintained by the planning scene.
Definition at line 979 of file planning_scene_monitor.cpp.
|
protected |
Definition at line 851 of file planning_scene_monitor.cpp.
|
protected |
Definition at line 888 of file planning_scene_monitor.cpp.
|
protected |
Definition at line 783 of file planning_scene_monitor.cpp.
|
protected |
Definition at line 927 of file planning_scene_monitor.cpp.
|
protected |
Definition at line 879 of file planning_scene_monitor.cpp.
|
inline |
Get the default attached padding.
Definition at line 263 of file planning_scene_monitor.h.
|
inline |
Get the default object padding.
Definition at line 257 of file planning_scene_monitor.h.
|
inline |
Get the default robot padding.
Definition at line 245 of file planning_scene_monitor.h.
|
inline |
Get the default robot scaling.
Definition at line 251 of file planning_scene_monitor.h.
|
inline |
Return the time when the last update was made to the planning scene (by any monitor)
Definition at line 399 of file planning_scene_monitor.h.
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 476 of file planning_scene_monitor.cpp.
|
inline |
Get the name of this monitor.
Definition at line 182 of file planning_scene_monitor.h.
|
inline |
Avoid this function! Returns an unsafe pointer to the current planning scene.
Definition at line 212 of file planning_scene_monitor.h.
|
inline |
Avoid this function! Returns an unsafe pointer to the current planning scene.
Definition at line 220 of file planning_scene_monitor.h.
|
inline |
Get the maximum frequency at which planning scenes are published (Hz)
Definition at line 294 of file planning_scene_monitor.h.
|
inline |
Get the stored robot description.
Definition at line 239 of file planning_scene_monitor.h.
|
inline |
Definition at line 193 of file planning_scene_monitor.h.
|
inline |
Get the user kinematic model loader.
Definition at line 188 of file planning_scene_monitor.h.
|
protected |
Definition at line 1106 of file planning_scene_monitor.cpp.
|
inline |
Get the stored instance of the stored current state monitor.
Definition at line 301 of file planning_scene_monitor.h.
|
inline |
Definition at line 306 of file planning_scene_monitor.h.
|
inline |
Get the maximum frequency (Hz) at which the current state of the planning scene is updated.
Definition at line 340 of file planning_scene_monitor.h.
|
inline |
Get the instance of the TF client that was passed to the constructor of this class.
Definition at line 269 of file planning_scene_monitor.h.
|
protected |
Definition at line 835 of file planning_scene_monitor.cpp.
|
protected |
Definition at line 910 of file planning_scene_monitor.cpp.
|
protected |
Definition at line 820 of file planning_scene_monitor.cpp.
|
protected |
Definition at line 950 of file planning_scene_monitor.cpp.
|
protected |
Definition at line 863 of file planning_scene_monitor.cpp.
|
protected |
Initialize the planning scene monitor.
scene | The 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.
|
protected |
Lock the scene for reading (multiple threads can lock for reading at the same time)
Definition at line 1053 of file planning_scene_monitor.cpp.
|
protected |
Lock the scene for writing (only one thread can lock for writing and no other thread can lock for reading)
Definition at line 1067 of file planning_scene_monitor.cpp.
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 311 of file planning_scene_monitor.cpp.
bool planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneMessage | ( | const moveit_msgs::msg::PlanningScene & | scene | ) |
Definition at line 650 of file planning_scene_monitor.cpp.
|
protected |
Callback for a new planning scene world.
Definition at line 729 of file planning_scene_monitor.cpp.
|
protected |
Callback for octomap updates.
Definition at line 1342 of file planning_scene_monitor.cpp.
|
delete |
PlanningSceneMonitor cannot be copy-assigned.
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.
service_name | The topic to provide the service |
Definition at line 575 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::publishDebugInformation | ( | bool | flag | ) |
Definition at line 1487 of file planning_scene_monitor.cpp.
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.
service_name | The 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 530 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::setPlanningScenePublishingFrequency | ( | double | hz | ) |
Set the maximum frequency at which planning scenes are being published.
Definition at line 1437 of file planning_scene_monitor.cpp.
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.
hz | the update frequency. By default this is 10Hz. |
Definition at line 1366 of file planning_scene_monitor.cpp.
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 374 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::startSceneMonitor | ( | const std::string & | scene_topic = DEFAULT_PLANNING_SCENE_TOPIC | ) |
Start the scene monitor (ROS topic-based)
scene_topic | The name of the planning scene topic |
Definition at line 1081 of file planning_scene_monitor.cpp.
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.
joint_states_topic | the topic to listen to for joint states |
attached_objects_topic | the topic to listen to for attached collision objects |
Definition at line 1230 of file planning_scene_monitor.cpp.
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:
collision_objects_topic | The topic on which to listen for collision objects |
planning_scene_world_topic | The topic to listen to for world scene geometry |
load_octomap_monitor | Flag to disable octomap monitor if desired |
Definition at line 1166 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::stopPublishingPlanningScene | ( | ) |
Stop publishing the maintained planning scene.
Definition at line 360 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::stopSceneMonitor | ( | ) |
Stop the scene monitor.
Definition at line 1097 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::stopStateMonitor | ( | ) |
Stop the state monitor.
Definition at line 1270 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::stopWorldGeometryMonitor | ( | ) |
Stop the world geometry monitor.
Definition at line 1214 of file planning_scene_monitor.cpp.
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 519 of file planning_scene_monitor.cpp.
|
protected |
Unlock the scene from reading (multiple threads can lock for reading at the same time)
Definition at line 1060 of file planning_scene_monitor.cpp.
|
protected |
Lock the scene from writing (only one thread can lock for writing and no other thread can lock for reading)
Definition at line 1074 of file planning_scene_monitor.cpp.
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 1472 of file planning_scene_monitor.cpp.
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 1395 of file planning_scene_monitor.cpp.
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 514 of file planning_scene_monitor.cpp.
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 509 of file planning_scene_monitor.cpp.
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 998 of file planning_scene_monitor.cpp.
|
friend |
Definition at line 619 of file planning_scene_monitor.h.
|
friend |
Definition at line 620 of file planning_scene_monitor.h.
|
protected |
Definition at line 553 of file planning_scene_monitor.h.
|
protected |
Definition at line 531 of file planning_scene_monitor.h.
|
protected |
Definition at line 554 of file planning_scene_monitor.h.
|
protected |
Definition at line 532 of file planning_scene_monitor.h.
|
protected |
Definition at line 542 of file planning_scene_monitor.h.
|
static |
The name of the topic used by default for attached collision objects.
Definition at line 100 of file planning_scene_monitor.h.
|
protected |
default attached padding
Definition at line 513 of file planning_scene_monitor.h.
|
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.
|
static |
The name of the topic used by default for receiving joint states.
Definition at line 97 of file planning_scene_monitor.h.
|
protected |
default object padding
Definition at line 511 of file planning_scene_monitor.h.
|
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.
|
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.
|
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.
|
protected |
default robot link padding
Definition at line 515 of file planning_scene_monitor.h.
|
protected |
default robot link scale
Definition at line 517 of file planning_scene_monitor.h.
|
protected |
default robot padding
Definition at line 507 of file planning_scene_monitor.h.
|
protected |
default robot scaling
Definition at line 509 of file planning_scene_monitor.h.
|
protected |
Definition at line 536 of file planning_scene_monitor.h.
|
protected |
Last time the state was updated.
Definition at line 490 of file planning_scene_monitor.h.
|
protected |
mutex for stored scene
Definition at line 489 of file planning_scene_monitor.h.
|
protected |
Definition at line 552 of file planning_scene_monitor.h.
|
protected |
The name of this scene monitor.
Definition at line 483 of file planning_scene_monitor.h.
|
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.
|
protected |
Definition at line 524 of file planning_scene_monitor.h.
|
protected |
Definition at line 525 of file planning_scene_monitor.h.
|
protected |
Last time the robot has moved.
Definition at line 492 of file planning_scene_monitor.h.
|
protected |
Definition at line 539 of file planning_scene_monitor.h.
|
protected |
Definition at line 487 of file planning_scene_monitor.h.
|
protected |
Definition at line 520 of file planning_scene_monitor.h.
|
protected |
Definition at line 528 of file planning_scene_monitor.h.
|
protected |
Definition at line 529 of file planning_scene_monitor.h.
|
protected |
Definition at line 497 of file planning_scene_monitor.h.
|
protected |
Definition at line 498 of file planning_scene_monitor.h.
|
protected |
Definition at line 499 of file planning_scene_monitor.h.
|
protected |
Definition at line 521 of file planning_scene_monitor.h.
|
protected |
Definition at line 522 of file planning_scene_monitor.h.
|
protected |
Definition at line 523 of file planning_scene_monitor.h.
|
protected |
Definition at line 504 of file planning_scene_monitor.h.
|
protected |
Definition at line 485 of file planning_scene_monitor.h.
|
protected |
Definition at line 486 of file planning_scene_monitor.h.
|
protected |
if diffs are monitored, this is the pointer to the parent scene
Definition at line 488 of file planning_scene_monitor.h.
|
mutableprotected |
Definition at line 555 of file planning_scene_monitor.h.
|
protected |
Definition at line 501 of file planning_scene_monitor.h.
|
protected |
Definition at line 502 of file planning_scene_monitor.h.
|
protected |
Definition at line 559 of file planning_scene_monitor.h.
|
protected |
lock access to update_callbacks_
Definition at line 558 of file planning_scene_monitor.h.