Public Member Functions | Private Member Functions | Private Attributes
planning_scene_monitor::CurrentStateMonitor Class Reference

Monitors the joint_states topic and tf to maintain the current state of the robot. More...

#include <current_state_monitor.h>

List of all members.

Public Member Functions

void addUpdateCallback (const JointStateUpdateCallback &fn)
 Add a function that will be called whenever the joint state is updated.
void clearUpdateCallbacks ()
 Clear the functions to be called when an update to the joint state is received.
 CurrentStateMonitor (const robot_model::RobotModelConstPtr &kmodel, const boost::shared_ptr< tf::Transformer > &tf)
 Constructor.
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").
robot_state::RobotStatePtr getCurrentState () const
 Get the current state.
std::pair
< robot_state::RobotStatePtr,
ros::Time
getCurrentStateAndTime () const
 Get the current state and its time stamp.
ros::Time getCurrentStateTime () const
 Get the time stamp for the current state.
std::map< std::string, double > getCurrentStateValues () const
 Get the current state values as a map from joint names to joint state values.
std::string getMonitoredTopic () const
 Get the name of the topic being monitored. Returns an empty string if the monitor is inactive.
const ros::TimegetMonitorStartTime () const
 Get the time point when the monitor was started.
const
robot_model::RobotModelConstPtr
getRobotModel () const
 Get the RobotModel for which we are monitoring state.
bool haveCompleteState () const
 Query whether we have joint state information for all DOFs in the kinematic model.
bool haveCompleteState (const ros::Duration &age) const
 Query whether we have joint state information for all DOFs in the kinematic model.
bool haveCompleteState (std::vector< std::string > &missing_joints) const
 Query whether we have joint state information for all DOFs in the kinematic model.
bool haveCompleteState (const ros::Duration &age, std::vector< std::string > &missing_states) const
 Query whether we have joint state information for all DOFs in the kinematic model.
bool isActive () const
 Check if the state monitor is started.
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.
void startStateMonitor (const std::string &joint_states_topic="joint_states")
 Start monitoring joint states on a particular topic.
void stopStateMonitor ()
 Stop monitoring the "joint_states" topic.
bool waitForCurrentState (double wait_time) const
 Wait for at most wait_time seconds until the complete current state is known. Return true if the full state is known.
bool waitForCurrentState (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.
 ~CurrentStateMonitor ()

Private Member Functions

bool isPassiveDOF (const std::string &dof) const
void jointStateCallback (const sensor_msgs::JointStateConstPtr &joint_state)

Private Attributes

ros::Time current_state_time_
double error_
ros::Subscriber joint_state_subscriber_
std::map< std::string, ros::Timejoint_time_
robot_model::RobotModelConstPtr kmodel_
robot_state::RobotState kstate_
ros::Time monitor_start_time_
ros::NodeHandle nh_
robot_state::JointStateroot_
bool state_monitor_started_
boost::mutex state_update_lock_
boost::shared_ptr
< tf::Transformer
tf_
std::vector
< JointStateUpdateCallback
update_callbacks_

Detailed Description

Monitors the joint_states topic and tf to maintain the current state of the robot.

Definition at line 55 of file current_state_monitor.h.


Constructor & Destructor Documentation

Constructor.

Parameters:
kmodelThe current kinematic model to build on
tfA pointer to the tf transformer to use

Definition at line 41 of file current_state_monitor.cpp.

Definition at line 47 of file current_state_monitor.cpp.


Member Function Documentation

Add a function that will be called whenever the joint state is updated.

Definition at line 80 of file current_state_monitor.cpp.

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

Definition at line 86 of file current_state_monitor.cpp.

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").

Returns:
The stored value for the "allowed bounds error"

Definition at line 158 of file current_state_monitor.h.

Get the current state.

Returns:
Returns the current state

Definition at line 52 of file current_state_monitor.cpp.

Get the current state and its time stamp.

Returns:
Returns a pair of the current state and its time stamp

Definition at line 65 of file current_state_monitor.cpp.

Get the time stamp for the current state.

Definition at line 59 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.

Returns:
Returns the map from joint names to joint state values

Definition at line 72 of file current_state_monitor.cpp.

Get the name of the topic being monitored. Returns an empty string if the monitor is inactive.

Definition at line 121 of file current_state_monitor.cpp.

Get the time point when the monitor was started.

Definition at line 134 of file current_state_monitor.h.

Get the RobotModel for which we are monitoring state.

Definition at line 80 of file current_state_monitor.h.

Query whether we have joint state information for all DOFs in the kinematic model.

Returns:
False if we have no joint state information for one or more of the joints

Definition at line 151 of file current_state_monitor.cpp.

Query whether we have joint state information for all DOFs in the kinematic model.

Returns:
False if we have no joint state information for one of the joints or if our state information is more than age old

Definition at line 184 of file current_state_monitor.cpp.

bool planning_scene_monitor::CurrentStateMonitor::haveCompleteState ( std::vector< std::string > &  missing_joints) const

Query whether we have joint state information for all DOFs in the kinematic model.

Parameters:
missing_jointsReturns the list of joints that are missing
Returns:
False if we have no joint state information for one or more of the joints

Definition at line 168 of file current_state_monitor.cpp.

bool planning_scene_monitor::CurrentStateMonitor::haveCompleteState ( const ros::Duration age,
std::vector< std::string > &  missing_states 
) const

Query whether we have joint state information for all DOFs in the kinematic model.

Parameters:
ageThe max allowed age of the joint state information
missing_statesReturns the list of joints that are missing
Returns:
False if we have no joint state information for one of the joints or if our state information is more than age old

Definition at line 212 of file current_state_monitor.cpp.

Check if the state monitor is started.

Definition at line 106 of file current_state_monitor.cpp.

bool planning_scene_monitor::CurrentStateMonitor::isPassiveDOF ( const std::string &  dof) const [private]

Definition at line 129 of file current_state_monitor.cpp.

void planning_scene_monitor::CurrentStateMonitor::jointStateCallback ( const sensor_msgs::JointStateConstPtr &  joint_state) [private]

Definition at line 283 of file current_state_monitor.cpp.

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.

Parameters:
errorThe specified value for the "allowed bounds error". The default is machine precision.

Definition at line 149 of file current_state_monitor.h.

void planning_scene_monitor::CurrentStateMonitor::startStateMonitor ( const std::string &  joint_states_topic = "joint_states")

Start monitoring joint states on a particular topic.

Parameters:
joint_states_topicThe topic name for joint states (defaults to "joint_states")

Definition at line 91 of file current_state_monitor.cpp.

Stop monitoring the "joint_states" topic.

Definition at line 111 of file current_state_monitor.cpp.

Wait for at most wait_time seconds until the complete current state is known. Return true if the full state is known.

Definition at line 243 of file current_state_monitor.cpp.

bool planning_scene_monitor::CurrentStateMonitor::waitForCurrentState ( 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 256 of file current_state_monitor.cpp.


Member Data Documentation

Definition at line 178 of file current_state_monitor.h.

Definition at line 176 of file current_state_monitor.h.

Definition at line 177 of file current_state_monitor.h.

Definition at line 173 of file current_state_monitor.h.

Definition at line 170 of file current_state_monitor.h.

Definition at line 171 of file current_state_monitor.h.

Definition at line 175 of file current_state_monitor.h.

Definition at line 168 of file current_state_monitor.h.

Definition at line 172 of file current_state_monitor.h.

Definition at line 174 of file current_state_monitor.h.

Definition at line 180 of file current_state_monitor.h.

Definition at line 169 of file current_state_monitor.h.

Definition at line 181 of file current_state_monitor.h.


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


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:31:40