#include <current_state_monitor.h>
| Public Member Functions | |
| void | addUpdateCallback (const JointStateUpdateCallback &fn) | 
| Add a function that will be called whenever the joint state is updated.  More... | |
| void | clearUpdateCallbacks () | 
| Clear the functions to be called when an update to the joint state is received.  More... | |
| CurrentStateMonitor (const moveit::core::RobotModelConstPtr &robot_model, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer) | |
| Constructor.  More... | |
| CurrentStateMonitor (const moveit::core::RobotModelConstPtr &robot_model, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer, const ros::NodeHandle &nh) | |
| Constructor.  More... | |
| void | enableCopyDynamics (bool enabled) | 
| Allow the joint_state arrrays velocity and effort to be copied into the robot state this is useful in some but not all applications.  More... | |
| double | getBoundsError () const | 
| When a joint value is received to be out of bounds, it is changed slightly to fit within bounds, if the difference is less than a specified value (labeled the "allowed bounds error").  More... | |
| moveit::core::RobotStatePtr | getCurrentState () const | 
| Get the current state.  More... | |
| std::pair< moveit::core::RobotStatePtr, ros::Time > | getCurrentStateAndTime (const std::string &group="") const | 
| Get the current state and its time stamp.  More... | |
| ros::Time | getCurrentStateTime (const std::string &group="") const | 
| Get the time stamp for the current state.  More... | |
| std::map< std::string, double > | getCurrentStateValues () const | 
| Get the current state values as a map from joint names to joint state values.  More... | |
| std::string | getMonitoredTopic () const | 
| Get the name of the topic being monitored. Returns an empty string if the monitor is inactive.  More... | |
| const ros::Time & | getMonitorStartTime () const | 
| Get the time point when the monitor was started.  More... | |
| const moveit::core::RobotModelConstPtr & | getRobotModel () const | 
| Get the RobotModel for which we are monitoring state.  More... | |
| bool | haveCompleteState (const ros::Duration &age, const std::string &group="") const | 
| Query whether we have joint state information for all DOFs in the kinematic model.  More... | |
| bool | haveCompleteState (const ros::Duration &age, std::vector< std::string > &missing_joints, const std::string &group="") const | 
| Query whether we have joint state information for all DOFs in the kinematic model.  More... | |
| bool | haveCompleteState (const ros::Time &oldest_allowed_update_time, const std::string &group="") const | 
| Query whether we have joint state information for all DOFs in the kinematic model.  More... | |
| bool | haveCompleteState (const ros::Time &oldest_allowed_update_time, std::vector< std::string > &missing_joints, const std::string &group="") const | 
| Query whether we have joint state information for all DOFs in the kinematic model.  More... | |
| bool | haveCompleteState (const std::string &group="") const | 
| Query whether we have joint state information for all DOFs in the kinematic model.  More... | |
| bool | haveCompleteState (std::vector< std::string > &missing_joints, const std::string &group="") const | 
| Query whether we have joint state information for all DOFs in the kinematic model.  More... | |
| bool | isActive () const | 
| Check if the state monitor is started.  More... | |
| void | setBoundsError (double error) | 
| When a joint value is received to be out of bounds, it is changed slightly to fit within bounds, if the difference is less than a specified value (labeled the "allowed bounds error"). This value can be set using this function.  More... | |
| void | setToCurrentState (moveit::core::RobotState &upd) const | 
| Set the state upd to the current state maintained by this class.  More... | |
| void | startStateMonitor (const std::string &joint_states_topic="joint_states") | 
| Start monitoring joint states on a particular topic.  More... | |
| void | stopStateMonitor () | 
| Stop monitoring the "joint_states" topic.  More... | |
| bool | waitForCompleteState (const std::string &group, double wait_time) const | 
| Wait for at most wait_time seconds until the joint values from the group group are known. Return true if values for all joints in group are known.  More... | |
| bool | waitForCompleteState (double wait_time) const | 
| Wait for at most wait_time seconds until the complete robot state is known.  More... | |
| bool | waitForCurrentState (const ros::Time t=ros::Time::now(), double wait_time=1.0) const | 
| Wait for at most wait_time seconds (default 1s) for a robot state more recent than t.  More... | |
| ~CurrentStateMonitor () | |
| Private Types | |
| using | TFConnection = boost::signals2::connection | 
| Private Member Functions | |
| ros::Time | getCurrentStateTimeHelper (const std::string &group="") const | 
| bool | haveCompleteStateHelper (const ros::Time &oldest_allowed_update_time, std::vector< std::string > *missing_joints, const std::string &group) const | 
| void | jointStateCallback (const sensor_msgs::JointStateConstPtr &joint_state) | 
| void | tfCallback () | 
| Private Attributes | |
| bool | copy_dynamics_ | 
| double | error_ | 
| ros::Subscriber | joint_state_subscriber_ | 
| std::map< const moveit::core::JointModel *, ros::Time > | joint_time_ | 
| ros::Time | monitor_start_time_ | 
| ros::NodeHandle | nh_ | 
| moveit::core::RobotModelConstPtr | robot_model_ | 
| moveit::core::RobotState | robot_state_ | 
| bool | state_monitor_started_ | 
| boost::condition_variable | state_update_condition_ | 
| boost::mutex | state_update_lock_ | 
| std::shared_ptr< tf2_ros::Buffer > | tf_buffer_ | 
| std::shared_ptr< TFConnection > | tf_connection_ | 
| std::vector< JointStateUpdateCallback > | update_callbacks_ | 
Monitors the joint_states topic and tf to maintain the current state of the robot.
Definition at line 84 of file current_state_monitor.h.
| 
 | private | 
Definition at line 86 of file current_state_monitor.h.
| planning_scene_monitor::CurrentStateMonitor::CurrentStateMonitor | ( | const moveit::core::RobotModelConstPtr & | robot_model, | 
| const std::shared_ptr< tf2_ros::Buffer > & | tf_buffer | ||
| ) | 
Constructor.
| robot_model | The current kinematic model to build on | 
| tf_buffer | A pointer to the tf2_ros Buffer to use | 
Definition at line 48 of file current_state_monitor.cpp.
| planning_scene_monitor::CurrentStateMonitor::CurrentStateMonitor | ( | const moveit::core::RobotModelConstPtr & | robot_model, | 
| const std::shared_ptr< tf2_ros::Buffer > & | tf_buffer, | ||
| const ros::NodeHandle & | nh | ||
| ) | 
Constructor.
| robot_model | The current kinematic model to build on | 
| tf_buffer | A pointer to the tf2_ros Buffer to use | 
| nh | A ros::NodeHandle to pass node specific options | 
Definition at line 54 of file current_state_monitor.cpp.
| planning_scene_monitor::CurrentStateMonitor::~CurrentStateMonitor | ( | ) | 
Definition at line 67 of file current_state_monitor.cpp.
| void planning_scene_monitor::CurrentStateMonitor::addUpdateCallback | ( | const JointStateUpdateCallback & | fn | ) | 
Add a function that will be called whenever the joint state is updated.
Definition at line 162 of file current_state_monitor.cpp.
| void planning_scene_monitor::CurrentStateMonitor::clearUpdateCallbacks | ( | ) | 
Clear the functions to be called when an update to the joint state is received.
Definition at line 168 of file current_state_monitor.cpp.
| 
 | inline | 
Allow the joint_state arrrays velocity and effort to be copied into the robot state this is useful in some but not all applications.
Definition at line 258 of file current_state_monitor.h.
| 
 | inline | 
When a joint value is received to be out of bounds, it is changed slightly to fit within bounds, if the difference is less than a specified value (labeled the "allowed bounds error").
Definition at line 250 of file current_state_monitor.h.
| moveit::core::RobotStatePtr planning_scene_monitor::CurrentStateMonitor::getCurrentState | ( | ) | const | 
Get the current state.
Definition at line 72 of file current_state_monitor.cpp.
| std::pair< moveit::core::RobotStatePtr, ros::Time > planning_scene_monitor::CurrentStateMonitor::getCurrentStateAndTime | ( | const std::string & | group = "" | ) | const | 
Get the current state and its time stamp.
| group | The name of the joint group whose current state is asked, defaults to empty string, which means all the active joints. | 
Definition at line 119 of file current_state_monitor.cpp.
| ros::Time planning_scene_monitor::CurrentStateMonitor::getCurrentStateTime | ( | const std::string & | group = "" | ) | const | 
Get the time stamp for the current state.
| group | The name of the joint group whose current state is asked, defaults to empty string, which means all the active joints. | 
Definition at line 112 of file current_state_monitor.cpp.
| 
 | private | 
Lock-free method that is used by getCurrentStateTime and getCurrentStateAndTime methods.
Definition at line 79 of file current_state_monitor.cpp.
| std::map< std::string, double > planning_scene_monitor::CurrentStateMonitor::getCurrentStateValues | ( | ) | const | 
Get the current state values as a map from joint names to joint state values.
Definition at line 126 of file current_state_monitor.cpp.
| std::string planning_scene_monitor::CurrentStateMonitor::getMonitoredTopic | ( | ) | const | 
Get the name of the topic being monitored. Returns an empty string if the monitor is inactive.
Definition at line 213 of file current_state_monitor.cpp.
| 
 | inline | 
Get the time point when the monitor was started.
Definition at line 226 of file current_state_monitor.h.
| 
 | inline | 
Get the RobotModel for which we are monitoring state.
Definition at line 120 of file current_state_monitor.h.
| 
 | inline | 
Query whether we have joint state information for all DOFs in the kinematic model.
| age | Joint information must be at most this old | 
Definition at line 150 of file current_state_monitor.h.
| 
 | inline | 
Query whether we have joint state information for all DOFs in the kinematic model.
Definition at line 179 of file current_state_monitor.h.
| 
 | inline | 
Query whether we have joint state information for all DOFs in the kinematic model.
| oldest_allowed_update_time | All joint information must be from this time or more current | 
Definition at line 140 of file current_state_monitor.h.
| 
 | inline | 
Query whether we have joint state information for all DOFs in the kinematic model.
| oldest_allowed_update_time | All joint information must be from this time or more current | 
| missing_joints | Returns the list of joints that are missing | 
Definition at line 169 of file current_state_monitor.h.
| 
 | inline | 
Query whether we have joint state information for all DOFs in the kinematic model.
Definition at line 131 of file current_state_monitor.h.
| 
 | inline | 
Query whether we have joint state information for all DOFs in the kinematic model.
| missing_joints | Returns the list of joints that are missing | 
Definition at line 159 of file current_state_monitor.h.
| 
 | private | 
Definition at line 221 of file current_state_monitor.cpp.
| bool planning_scene_monitor::CurrentStateMonitor::isActive | ( | ) | const | 
Check if the state monitor is started.
Definition at line 193 of file current_state_monitor.cpp.
| 
 | private | 
Definition at line 320 of file current_state_monitor.cpp.
| 
 | inline | 
When a joint value is received to be out of bounds, it is changed slightly to fit within bounds, if the difference is less than a specified value (labeled the "allowed bounds error"). This value can be set using this function.
| error | The specified value for the "allowed bounds error". The default is machine precision. | 
Definition at line 241 of file current_state_monitor.h.
| void planning_scene_monitor::CurrentStateMonitor::setToCurrentState | ( | moveit::core::RobotState & | upd | ) | const | 
Set the state upd to the current state maintained by this class.
Definition at line 137 of file current_state_monitor.cpp.
| void planning_scene_monitor::CurrentStateMonitor::startStateMonitor | ( | const std::string & | joint_states_topic = "joint_states" | ) | 
Start monitoring joint states on a particular topic.
| joint_states_topic | The topic name for joint states (defaults to "joint_states") | 
Definition at line 173 of file current_state_monitor.cpp.
| void planning_scene_monitor::CurrentStateMonitor::stopStateMonitor | ( | ) | 
Stop monitoring the "joint_states" topic.
Definition at line 198 of file current_state_monitor.cpp.
| 
 | private | 
Definition at line 410 of file current_state_monitor.cpp.
| bool planning_scene_monitor::CurrentStateMonitor::waitForCompleteState | ( | const std::string & | group, | 
| double | wait_time | ||
| ) | const | 
Wait for at most wait_time seconds until the joint values from the group group are known. Return true if values for all joints in group are known.
Definition at line 301 of file current_state_monitor.cpp.
| bool planning_scene_monitor::CurrentStateMonitor::waitForCompleteState | ( | double | wait_time | ) | const | 
Wait for at most wait_time seconds until the complete robot state is known.
Definition at line 288 of file current_state_monitor.cpp.
| bool planning_scene_monitor::CurrentStateMonitor::waitForCurrentState | ( | const ros::Time | t = ros::Time::now(), | 
| double | wait_time = 1.0 | ||
| ) | const | 
Wait for at most wait_time seconds (default 1s) for a robot state more recent than t.
Definition at line 266 of file current_state_monitor.cpp.
| 
 | private | 
Definition at line 280 of file current_state_monitor.h.
| 
 | private | 
Definition at line 282 of file current_state_monitor.h.
| 
 | private | 
Definition at line 283 of file current_state_monitor.h.
| 
 | private | 
Definition at line 278 of file current_state_monitor.h.
| 
 | private | 
Definition at line 281 of file current_state_monitor.h.
| 
 | private | 
Definition at line 274 of file current_state_monitor.h.
| 
 | private | 
Definition at line 276 of file current_state_monitor.h.
| 
 | private | 
Definition at line 277 of file current_state_monitor.h.
| 
 | private | 
Definition at line 279 of file current_state_monitor.h.
| 
 | mutableprivate | 
Definition at line 286 of file current_state_monitor.h.
| 
 | mutableprivate | 
Definition at line 285 of file current_state_monitor.h.
| 
 | private | 
Definition at line 275 of file current_state_monitor.h.
| 
 | private | 
Definition at line 289 of file current_state_monitor.h.
| 
 | private | 
Definition at line 287 of file current_state_monitor.h.