PlanningSceneMonitor Subscribes to the topic planning_scene. More...
#include <planning_scene_monitor.h>
Classes | |
class | DynamicReconfigureImpl |
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 | |
void | addUpdateCallback (const boost::function< void(SceneUpdateType)> &fn) |
Add a function to be called when an update to the scene is received. | |
void | clearUpdateCallbacks () |
Clear the functions to be called when an update to the scene is received. | |
double | getDefaultAttachedObjectPadding () const |
Get the default attached padding. | |
double | getDefaultObjectPadding () const |
Get the default object padding. | |
double | getDefaultRobotPadding () const |
Get the default robot padding. | |
double | getDefaultRobotScale () const |
Get the default robot scaling. | |
const ros::Time & | getLastUpdateTime () const |
Return the time when the last update was made to the planning scene (by the monitor) | |
void | getMonitoredTopics (std::vector< std::string > &topics) const |
Get the topic names that the monitor is listening to. | |
const std::string & | getName () const |
Get the name of this monitor. | |
const planning_scene::PlanningScenePtr & | getPlanningScene () |
Get the planning scene. | |
const planning_scene::PlanningSceneConstPtr & | getPlanningScene () const |
Get the planning scene. | |
double | getPlanningScenePublishingFrequency () const |
Get the maximum frequency at which planning scenes are published (Hz) | |
const std::string & | getRobotDescription () const |
Get the stored robot description. | |
const robot_model::RobotModelConstPtr & | getRobotModel () const |
const robot_model_loader::RobotModelLoaderPtr & | getRobotModelLoader () const |
Get the user kinematic model loader. | |
const CurrentStateMonitorPtr & | getStateMonitor () const |
Get the stored instance of the stored current state monitor. | |
double | getStateUpdateFrequency () |
Get the maximum frequency (Hz) at which the current state of the planning scene is updated. | |
const boost::shared_ptr < tf::Transformer > & | getTFClient () const |
Get the instance of the TF client that was passed to the constructor of this class. | |
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 reading) | |
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. | |
PlanningSceneMonitor (const std::string &robot_description, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >(), const std::string &name="") | |
Constructor. | |
PlanningSceneMonitor (const robot_model_loader::RobotModelLoaderPtr &rml, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >(), const std::string &name="") | |
Constructor. | |
PlanningSceneMonitor (const planning_scene::PlanningScenePtr &scene, const std::string &robot_description, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >(), const std::string &name="") | |
Constructor. | |
PlanningSceneMonitor (const planning_scene::PlanningScenePtr &scene, const robot_model_loader::RobotModelLoaderPtr &rml, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >(), const std::string &name="") | |
Constructor. | |
void | publishDebugInformation (bool flag) |
void | setPlanningScenePublishingFrequency (double hz) |
Set the maximum frequency at which planning scenes are being published. | |
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. | |
void | startPublishingPlanningScene (SceneUpdateType event, const std::string &planning_scene_topic="monitored_planning_scene") |
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. | |
void | startSceneMonitor (const std::string &scene_topic="planning_scene") |
Start the scene monitor. | |
void | startStateMonitor (const std::string &joint_states_topic="joint_states", const std::string &attached_objects_topic="attached_collision_object") |
Start the current state monitor. | |
void | startWorldGeometryMonitor (const std::string &collision_objects_topic="collision_object", const std::string &collision_map_topic="collision_map", const std::string &planning_scene_world_topic="planning_scene_world") |
Start listening for objects in the world, the collision map and attached collision objects. Additionally, this function starts the OccupancyMapMonitor as well. | |
void | stopPublishingPlanningScene () |
Stop publishing the maintained planning scene. | |
void | stopSceneMonitor () |
Stop the scene monitor. | |
void | stopStateMonitor () |
Stop the state monitor. | |
void | stopWorldGeometryMonitor () |
Stop the world geometry monitor. | |
void | triggerSceneUpdateEvent (SceneUpdateType update_type) |
This function is called every time there is a change to the planning scene. | |
void | unlockSceneRead () |
Unlock the scene from reading (multiple threads can lock for reading at the same time) | |
void | unlockSceneWrite () |
Lock the scene from writing (only one thread can lock for writing and no other thread can lock for reading) | |
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. | |
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(). | |
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. | |
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. | |
~PlanningSceneMonitor () | |
Protected Types | |
typedef std::map< const robot_state::AttachedBody *, std::vector< std::pair < occupancy_map_monitor::ShapeHandle, std::size_t > > > | AttachedBodyShapeHandles |
typedef std::map< std::string, std::vector< std::pair < occupancy_map_monitor::ShapeHandle, Eigen::Affine3d * > > > | CollisionBodyShapeHandles |
typedef std::map< std::string, occupancy_map_monitor::ShapeHandle > | LinkShapeHandles |
Protected Member Functions | |
void | attachObjectCallback (const moveit_msgs::AttachedCollisionObjectConstPtr &obj) |
Callback for a new attached object msg. | |
void | collisionMapCallback (const moveit_msgs::CollisionMapConstPtr &map) |
Callback for a new collision map. | |
void | collisionObjectCallback (const moveit_msgs::CollisionObjectConstPtr &obj) |
Callback for a new collision object msg. | |
void | collisionObjectFailTFCallback (const moveit_msgs::CollisionObjectConstPtr &obj, tf::filter_failure_reasons::FilterFailureReason reason) |
Callback for a new collision object msg that failed to pass the TF filter. | |
void | configureCollisionMatrix (const planning_scene::PlanningScenePtr &scene) |
Configure the collision matrix for a particular scene. | |
void | configureDefaultPadding () |
Configure the default padding. | |
void | currentStateAttachedBodyUpdateCallback (robot_state::AttachedBody *attached_body, bool just_attached) |
Callback for a change for an attached object of the current state of the planning scene. | |
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. | |
void | excludeAttachedBodiesFromOctree () |
void | excludeAttachedBodyFromOctree (const robot_state::AttachedBody *attached_body) |
void | excludeRobotLinksFromOctree () |
void | excludeWorldObjectFromOctree (const collision_detection::World::ObjectConstPtr &obj) |
void | excludeWorldObjectsFromOctree () |
bool | getShapeTransformCache (const std::string &target_frame, const ros::Time &target_time, occupancy_map_monitor::ShapeTransformCache &cache) const |
void | includeAttachedBodiesInOctree () |
void | includeAttachedBodyInOctree (const robot_state::AttachedBody *attached_body) |
void | includeRobotLinksInOctree () |
void | includeWorldObjectInOctree (const collision_detection::World::ObjectConstPtr &obj) |
void | includeWorldObjectsInOctree () |
void | initialize (const planning_scene::PlanningScenePtr &scene) |
Initialize the planning scene monitor. | |
void | newPlanningSceneCallback (const moveit_msgs::PlanningSceneConstPtr &scene) |
Callback for a new planning scene msg. | |
void | newPlanningSceneWorldCallback (const moveit_msgs::PlanningSceneWorldConstPtr &world) |
Callback for a new planning scene world. | |
void | octomapUpdateCallback () |
Callback for octomap updates. | |
Protected Attributes | |
AttachedBodyShapeHandles | attached_body_shape_handles_ |
ros::Subscriber | attached_collision_object_subscriber_ |
CollisionBodyShapeHandles | collision_body_shape_handles_ |
boost::scoped_ptr < tf::MessageFilter < moveit_msgs::CollisionMap > > | collision_map_filter_ |
boost::scoped_ptr < message_filters::Subscriber < moveit_msgs::CollisionMap > > | collision_map_subscriber_ |
boost::scoped_ptr < tf::MessageFilter < moveit_msgs::CollisionObject > > | collision_object_filter_ |
boost::scoped_ptr < message_filters::Subscriber < moveit_msgs::CollisionObject > > | collision_object_subscriber_ |
CurrentStateMonitorPtr | current_state_monitor_ |
double | default_attached_padd_ |
default attached padding | |
double | default_object_padd_ |
default object padding | |
double | default_robot_padd_ |
default robot padding | |
double | default_robot_scale_ |
default robot scaling | |
ros::Time | last_update_time_ |
List of callbacks to trigger when updates are received. | |
LinkShapeHandles | link_shape_handles_ |
std::string | monitor_name_ |
The name of this scene monitor. | |
SceneUpdateType | new_scene_update_ |
boost::condition_variable_any | new_scene_update_condition_ |
ros::NodeHandle | nh_ |
mutex for stored scene | |
boost::scoped_ptr < occupancy_map_monitor::OccupancyMapMonitor > | octomap_monitor_ |
planning_scene::PlanningScenePtr | parent_scene_ |
ros::Publisher | planning_scene_publisher_ |
ros::Subscriber | planning_scene_subscriber_ |
ros::Subscriber | planning_scene_world_subscriber_ |
boost::scoped_ptr< boost::thread > | publish_planning_scene_ |
double | publish_planning_scene_frequency_ |
SceneUpdateType | publish_update_types_ |
std::string | robot_description_ |
ros::NodeHandle | root_nh_ |
planning_scene::PlanningScenePtr | scene_ |
planning_scene::PlanningSceneConstPtr | scene_const_ |
boost::shared_mutex | scene_update_mutex_ |
if diffs are monitored, this is the pointer to the parent scene | |
boost::recursive_mutex | shape_handles_lock_ |
boost::shared_ptr < tf::Transformer > | tf_ |
std::vector< boost::function < void(SceneUpdateType)> > | update_callbacks_ |
Private Member Functions | |
void | getUpdatedFrameTransforms (std::vector< geometry_msgs::TransformStamped > &transforms) |
Last time the state was updated. | |
void | onStateUpdate (const sensor_msgs::JointStateConstPtr &joint_state) |
void | scenePublishingThread () |
Private Attributes | |
double | dt_state_update_ |
the amount of time to wait in between updates to the robot state (in seconds) | |
ros::WallTime | last_state_update_ |
DynamicReconfigureImpl * | reconfigure_impl_ |
robot_model_loader::RobotModelLoaderPtr | rm_loader_ |
robot_model::RobotModelConstPtr | robot_model_ |
PlanningSceneMonitor Subscribes to the topic planning_scene.
Definition at line 58 of file planning_scene_monitor.h.
typedef std::map<const robot_state::AttachedBody*, std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t> > > planning_scene_monitor::PlanningSceneMonitor::AttachedBodyShapeHandles [protected] |
Definition at line 412 of file planning_scene_monitor.h.
typedef std::map<std::string, std::vector<std::pair<occupancy_map_monitor::ShapeHandle, Eigen::Affine3d*> > > planning_scene_monitor::PlanningSceneMonitor::CollisionBodyShapeHandles [protected] |
Definition at line 413 of file planning_scene_monitor.h.
typedef std::map<std::string, occupancy_map_monitor::ShapeHandle> planning_scene_monitor::PlanningSceneMonitor::LinkShapeHandles [protected] |
Definition at line 411 of file planning_scene_monitor.h.
Definition at line 62 of file planning_scene_monitor.h.
planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor | ( | const std::string & | robot_description, |
const boost::shared_ptr< tf::Transformer > & | tf = boost::shared_ptr<tf::Transformer>() , |
||
const std::string & | name = "" |
||
) |
Constructor.
robot_description | The name of the ROS parameter that contains the URDF (in string format) |
tf | A pointer to a tf::Transformer |
name | A name identifying this planning scene monitor |
Definition at line 103 of file planning_scene_monitor.cpp.
planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor | ( | const robot_model_loader::RobotModelLoaderPtr & | rml, |
const boost::shared_ptr< tf::Transformer > & | tf = boost::shared_ptr<tf::Transformer>() , |
||
const std::string & | name = "" |
||
) |
Constructor.
rml | A pointer to a kinematic model loader |
tf | A pointer to a tf::Transformer |
name | A name identifying this planning scene monitor |
Definition at line 118 of file planning_scene_monitor.cpp.
planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor | ( | const planning_scene::PlanningScenePtr & | scene, |
const std::string & | robot_description, | ||
const boost::shared_ptr< tf::Transformer > & | tf = boost::shared_ptr<tf::Transformer>() , |
||
const std::string & | name = "" |
||
) |
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 | A pointer to a tf::Transformer |
name | A name identifying this planning scene monitor |
Definition at line 110 of file planning_scene_monitor.cpp.
planning_scene_monitor::PlanningSceneMonitor::PlanningSceneMonitor | ( | const planning_scene::PlanningScenePtr & | scene, |
const robot_model_loader::RobotModelLoaderPtr & | rml, | ||
const boost::shared_ptr< tf::Transformer > & | tf = boost::shared_ptr<tf::Transformer>() , |
||
const std::string & | name = "" |
||
) |
Constructor.
scene | The scene instance to maintain up to date with monitored information |
rml | A pointer to a kinematic model loader |
tf | A pointer to a tf::Transformer |
name | A name identifying this planning scene monitor |
Definition at line 125 of file planning_scene_monitor.cpp.
Definition at line 132 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::addUpdateCallback | ( | const boost::function< void(SceneUpdateType)> & | fn | ) |
Add a function to be called when an update to the scene is received.
Definition at line 967 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::attachObjectCallback | ( | const moveit_msgs::AttachedCollisionObjectConstPtr & | obj | ) | [protected] |
Callback for a new attached object msg.
Definition at line 495 of file planning_scene_monitor.cpp.
Clear the functions to be called when an update to the scene is received.
Definition at line 973 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::collisionMapCallback | ( | const moveit_msgs::CollisionMapConstPtr & | map | ) | [protected] |
Callback for a new collision map.
Definition at line 509 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::collisionObjectCallback | ( | const moveit_msgs::CollisionObjectConstPtr & | obj | ) | [protected] |
Callback for a new collision object msg.
Definition at line 481 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::collisionObjectFailTFCallback | ( | const moveit_msgs::CollisionObjectConstPtr & | obj, |
tf::filter_failure_reasons::FilterFailureReason | reason | ||
) | [protected] |
Callback for a new collision object msg that failed to pass the TF filter.
Definition at line 474 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::configureCollisionMatrix | ( | const planning_scene::PlanningScenePtr & | scene | ) | [protected] |
Configure the collision matrix for a particular scene.
Definition at line 1057 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::configureDefaultPadding | ( | ) | [protected] |
Configure the default padding.
Definition at line 1099 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::currentStateAttachedBodyUpdateCallback | ( | robot_state::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 668 of file planning_scene_monitor.cpp.
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 679 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::excludeAttachedBodiesFromOctree | ( | ) | [protected] |
Definition at line 569 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::excludeAttachedBodyFromOctree | ( | const robot_state::AttachedBody * | attached_body | ) | [protected] |
Definition at line 601 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::excludeRobotLinksFromOctree | ( | ) | [protected] |
Definition at line 523 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::excludeWorldObjectFromOctree | ( | const collision_detection::World::ObjectConstPtr & | obj | ) | [protected] |
Definition at line 634 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::excludeWorldObjectsFromOctree | ( | ) | [protected] |
Definition at line 592 of file planning_scene_monitor.cpp.
double planning_scene_monitor::PlanningSceneMonitor::getDefaultAttachedObjectPadding | ( | ) | const [inline] |
Get the default attached padding.
Definition at line 191 of file planning_scene_monitor.h.
double planning_scene_monitor::PlanningSceneMonitor::getDefaultObjectPadding | ( | ) | const [inline] |
Get the default object padding.
Definition at line 185 of file planning_scene_monitor.h.
double planning_scene_monitor::PlanningSceneMonitor::getDefaultRobotPadding | ( | ) | const [inline] |
Get the default robot padding.
Definition at line 173 of file planning_scene_monitor.h.
double planning_scene_monitor::PlanningSceneMonitor::getDefaultRobotScale | ( | ) | const [inline] |
Get the default robot scaling.
Definition at line 179 of file planning_scene_monitor.h.
const ros::Time& planning_scene_monitor::PlanningSceneMonitor::getLastUpdateTime | ( | ) | const [inline] |
Return the time when the last update was made to the planning scene (by the monitor)
Definition at line 286 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 354 of file planning_scene_monitor.cpp.
const std::string& planning_scene_monitor::PlanningSceneMonitor::getName | ( | void | ) | const [inline] |
Get the name of this monitor.
Definition at line 123 of file planning_scene_monitor.h.
const planning_scene::PlanningScenePtr& planning_scene_monitor::PlanningSceneMonitor::getPlanningScene | ( | ) | [inline] |
Get the planning scene.
Definition at line 141 of file planning_scene_monitor.h.
const planning_scene::PlanningSceneConstPtr& planning_scene_monitor::PlanningSceneMonitor::getPlanningScene | ( | ) | const [inline] |
Get the planning scene.
Definition at line 148 of file planning_scene_monitor.h.
double planning_scene_monitor::PlanningSceneMonitor::getPlanningScenePublishingFrequency | ( | ) | const [inline] |
Get the maximum frequency at which planning scenes are published (Hz)
Definition at line 219 of file planning_scene_monitor.h.
const std::string& planning_scene_monitor::PlanningSceneMonitor::getRobotDescription | ( | ) | const [inline] |
Get the stored robot description.
Definition at line 167 of file planning_scene_monitor.h.
const robot_model::RobotModelConstPtr& planning_scene_monitor::PlanningSceneMonitor::getRobotModel | ( | ) | const [inline] |
Definition at line 134 of file planning_scene_monitor.h.
const robot_model_loader::RobotModelLoaderPtr& planning_scene_monitor::PlanningSceneMonitor::getRobotModelLoader | ( | ) | const [inline] |
Get the user kinematic model loader.
Definition at line 129 of file planning_scene_monitor.h.
bool planning_scene_monitor::PlanningSceneMonitor::getShapeTransformCache | ( | const std::string & | target_frame, |
const ros::Time & | target_time, | ||
occupancy_map_monitor::ShapeTransformCache & | cache | ||
) | const [protected] |
Definition at line 748 of file planning_scene_monitor.cpp.
const CurrentStateMonitorPtr& planning_scene_monitor::PlanningSceneMonitor::getStateMonitor | ( | ) | const [inline] |
Get the stored instance of the stored current state monitor.
Definition at line 226 of file planning_scene_monitor.h.
Get the maximum frequency (Hz) at which the current state of the planning scene is updated.
const boost::shared_ptr<tf::Transformer>& 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 197 of file planning_scene_monitor.h.
void planning_scene_monitor::PlanningSceneMonitor::getUpdatedFrameTransforms | ( | std::vector< geometry_msgs::TransformStamped > & | transforms | ) | [private] |
Last time the state was updated.
Definition at line 984 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::includeAttachedBodiesInOctree | ( | ) | [protected] |
Definition at line 558 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::includeAttachedBodyInOctree | ( | const robot_state::AttachedBody * | attached_body | ) | [protected] |
Definition at line 620 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::includeRobotLinksInOctree | ( | ) | [protected] |
Definition at line 546 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::includeWorldObjectInOctree | ( | const collision_detection::World::ObjectConstPtr & | obj | ) | [protected] |
Definition at line 654 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::includeWorldObjectsInOctree | ( | ) | [protected] |
Definition at line 581 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::initialize | ( | const planning_scene::PlanningScenePtr & | scene | ) | [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 152 of file planning_scene_monitor.cpp.
Lock the scene for reading (multiple threads can lock for reading at the same time)
Definition at line 698 of file planning_scene_monitor.cpp.
Lock the scene for writing (only one thread can lock for writing and no other thread can lock for reading)
Definition at line 712 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 205 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneCallback | ( | const moveit_msgs::PlanningSceneConstPtr & | scene | ) | [protected] |
Callback for a new planning scene msg.
Definition at line 403 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::newPlanningSceneWorldCallback | ( | const moveit_msgs::PlanningSceneWorldConstPtr & | world | ) | [protected] |
Callback for a new planning scene world.
Definition at line 459 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::octomapUpdateCallback | ( | ) | [protected] |
Callback for octomap updates.
Definition at line 914 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::onStateUpdate | ( | const sensor_msgs::JointStateConstPtr & | joint_state | ) | [private] |
Definition at line 903 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::publishDebugInformation | ( | bool | flag | ) |
Definition at line 1051 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::scenePublishingThread | ( | ) | [private] |
Definition at line 275 of file planning_scene_monitor.cpp.
Set the maximum frequency at which planning scenes are being published.
Definition at line 978 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 935 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::startPublishingPlanningScene | ( | SceneUpdateType | event, |
const std::string & | planning_scene_topic = "monitored_planning_scene" |
||
) |
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 263 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::startSceneMonitor | ( | const std::string & | scene_topic = "planning_scene" | ) |
Start the scene monitor.
scene_topic | The name of the planning scene topic |
Definition at line 726 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::startStateMonitor | ( | const std::string & | joint_states_topic = "joint_states" , |
const std::string & | attached_objects_topic = "attached_collision_object" |
||
) |
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 874 of file planning_scene_monitor.cpp.
void planning_scene_monitor::PlanningSceneMonitor::startWorldGeometryMonitor | ( | const std::string & | collision_objects_topic = "collision_object" , |
const std::string & | collision_map_topic = "collision_map" , |
||
const std::string & | planning_scene_world_topic = "planning_scene_world" |
||
) |
Start listening for objects in the world, the collision map and attached collision objects. Additionally, this function starts the OccupancyMapMonitor as well.
collision_objects_topic | The topic on which to listen for collision objects |
collision_map_topic | The topic on which to listen for the collision map |
planning_scene_world_topic | The topic to listen to for world scene geometry |
Definition at line 792 of file planning_scene_monitor.cpp.
Stop publishing the maintained planning scene.
Definition at line 249 of file planning_scene_monitor.cpp.
Stop the scene monitor.
Definition at line 739 of file planning_scene_monitor.cpp.
Stop the state monitor.
Definition at line 895 of file planning_scene_monitor.cpp.
Stop the world geometry monitor.
Definition at line 852 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 395 of file planning_scene_monitor.cpp.
Unlock the scene from reading (multiple threads can lock for reading at the same time)
Definition at line 705 of file planning_scene_monitor.cpp.
Lock the scene from writing (only one thread can lock for writing and no other thread can lock for reading)
Definition at line 719 of file planning_scene_monitor.cpp.
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 1033 of file planning_scene_monitor.cpp.
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 944 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 390 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 385 of file planning_scene_monitor.cpp.
AttachedBodyShapeHandles planning_scene_monitor::PlanningSceneMonitor::attached_body_shape_handles_ [protected] |
Definition at line 416 of file planning_scene_monitor.h.
ros::Subscriber planning_scene_monitor::PlanningSceneMonitor::attached_collision_object_subscriber_ [protected] |
Definition at line 396 of file planning_scene_monitor.h.
CollisionBodyShapeHandles planning_scene_monitor::PlanningSceneMonitor::collision_body_shape_handles_ [protected] |
Definition at line 417 of file planning_scene_monitor.h.
boost::scoped_ptr<tf::MessageFilter<moveit_msgs::CollisionMap> > planning_scene_monitor::PlanningSceneMonitor::collision_map_filter_ [protected] |
Definition at line 402 of file planning_scene_monitor.h.
boost::scoped_ptr<message_filters::Subscriber<moveit_msgs::CollisionMap> > planning_scene_monitor::PlanningSceneMonitor::collision_map_subscriber_ [protected] |
Definition at line 401 of file planning_scene_monitor.h.
boost::scoped_ptr<tf::MessageFilter<moveit_msgs::CollisionObject> > planning_scene_monitor::PlanningSceneMonitor::collision_object_filter_ [protected] |
Definition at line 399 of file planning_scene_monitor.h.
boost::scoped_ptr<message_filters::Subscriber<moveit_msgs::CollisionObject> > planning_scene_monitor::PlanningSceneMonitor::collision_object_subscriber_ [protected] |
Definition at line 398 of file planning_scene_monitor.h.
CurrentStateMonitorPtr planning_scene_monitor::PlanningSceneMonitor::current_state_monitor_ [protected] |
Definition at line 408 of file planning_scene_monitor.h.
double planning_scene_monitor::PlanningSceneMonitor::default_attached_padd_ [protected] |
default attached padding
Definition at line 382 of file planning_scene_monitor.h.
double planning_scene_monitor::PlanningSceneMonitor::default_object_padd_ [protected] |
default object padding
Definition at line 380 of file planning_scene_monitor.h.
double planning_scene_monitor::PlanningSceneMonitor::default_robot_padd_ [protected] |
default robot padding
Definition at line 376 of file planning_scene_monitor.h.
double planning_scene_monitor::PlanningSceneMonitor::default_robot_scale_ [protected] |
default robot scaling
Definition at line 378 of file planning_scene_monitor.h.
double planning_scene_monitor::PlanningSceneMonitor::dt_state_update_ [private] |
the amount of time to wait in between updates to the robot state (in seconds)
Definition at line 432 of file planning_scene_monitor.h.
the planning scene state is updated at a maximum specified frequency, and this timestamp is used to implement that functionality
Definition at line 436 of file planning_scene_monitor.h.
List of callbacks to trigger when updates are received.
Definition at line 421 of file planning_scene_monitor.h.
Definition at line 415 of file planning_scene_monitor.h.
std::string planning_scene_monitor::PlanningSceneMonitor::monitor_name_ [protected] |
The name of this scene monitor.
Definition at line 363 of file planning_scene_monitor.h.
Definition at line 389 of file planning_scene_monitor.h.
boost::condition_variable_any planning_scene_monitor::PlanningSceneMonitor::new_scene_update_condition_ [protected] |
Definition at line 390 of file planning_scene_monitor.h.
mutex for stored scene
Definition at line 370 of file planning_scene_monitor.h.
boost::scoped_ptr<occupancy_map_monitor::OccupancyMapMonitor> planning_scene_monitor::PlanningSceneMonitor::octomap_monitor_ [protected] |
Definition at line 405 of file planning_scene_monitor.h.
planning_scene::PlanningScenePtr planning_scene_monitor::PlanningSceneMonitor::parent_scene_ [protected] |
Definition at line 367 of file planning_scene_monitor.h.
Definition at line 385 of file planning_scene_monitor.h.
ros::Subscriber planning_scene_monitor::PlanningSceneMonitor::planning_scene_subscriber_ [protected] |
Definition at line 393 of file planning_scene_monitor.h.
ros::Subscriber planning_scene_monitor::PlanningSceneMonitor::planning_scene_world_subscriber_ [protected] |
Definition at line 394 of file planning_scene_monitor.h.
boost::scoped_ptr<boost::thread> planning_scene_monitor::PlanningSceneMonitor::publish_planning_scene_ [protected] |
Definition at line 386 of file planning_scene_monitor.h.
Definition at line 387 of file planning_scene_monitor.h.
Definition at line 388 of file planning_scene_monitor.h.
Definition at line 441 of file planning_scene_monitor.h.
robot_model_loader::RobotModelLoaderPtr planning_scene_monitor::PlanningSceneMonitor::rm_loader_ [private] |
Definition at line 438 of file planning_scene_monitor.h.
std::string planning_scene_monitor::PlanningSceneMonitor::robot_description_ [protected] |
Definition at line 373 of file planning_scene_monitor.h.
robot_model::RobotModelConstPtr planning_scene_monitor::PlanningSceneMonitor::robot_model_ [private] |
Definition at line 439 of file planning_scene_monitor.h.
Definition at line 371 of file planning_scene_monitor.h.
Definition at line 365 of file planning_scene_monitor.h.
planning_scene::PlanningSceneConstPtr planning_scene_monitor::PlanningSceneMonitor::scene_const_ [protected] |
Definition at line 366 of file planning_scene_monitor.h.
boost::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 368 of file planning_scene_monitor.h.
boost::recursive_mutex planning_scene_monitor::PlanningSceneMonitor::shape_handles_lock_ [mutable, protected] |
Definition at line 418 of file planning_scene_monitor.h.
boost::shared_ptr<tf::Transformer> planning_scene_monitor::PlanningSceneMonitor::tf_ [protected] |
Definition at line 372 of file planning_scene_monitor.h.
std::vector<boost::function<void(SceneUpdateType)> > planning_scene_monitor::PlanningSceneMonitor::update_callbacks_ [protected] |
Definition at line 420 of file planning_scene_monitor.h.