Public Member Functions | Protected Member Functions | Protected Attributes
planning_environment::KinematicModelStateMonitor Class Reference

KinematicModelStateMonitor is a class that monitors the robot state for the kinematic model defined in RobotModels If the pose is not included, the robot state is the frame of the link it attaches to the world. If the pose is included, the frame of the robot is the one in which the pose is published. More...

#include <kinematic_model_state_monitor.h>

Inheritance diagram for planning_environment::KinematicModelStateMonitor:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void addOnStateUpdateCallback (const boost::function< void(const sensor_msgs::JointStateConstPtr &joint_state)> &callback)
bool allJointsUpdated (ros::Duration dur=ros::Duration()) const
bool getCachedJointStateValues (const ros::Time &time, std::map< std::string, double > &ret_map) const
std::map< std::string, double > getCurrentJointStateValues () const
bool getCurrentRobotState (arm_navigation_msgs::RobotState &robot_state) const
const
planning_models::KinematicModel
getKinematicModel (void) const
 Get the kinematic model that is being used to check for validity.
RobotModelsgetRobotModels (void) const
 Get the instance of RobotModels that is being used.
tf::TransformListenergetTransformListener (void) const
 Return the transform listener.
bool haveState (void) const
 Return true if a full joint state has been received (including pose, if pose inclusion is enabled)
bool isJointStateUpdated (double sec) const
 Return true if a joint state has been received in the last sec seconds. If sec < 10us, this function always returns true.
bool isPoseUpdated (double sec) const
 Return true if a pose has been received in the last sec seconds. If sec < 10us, this function always returns true.
bool isStateMonitorStarted (void) const
 Check if the state monitor is currently started.
 KinematicModelStateMonitor (RobotModels *rm, tf::TransformListener *tf)
const ros::TimelastJointStateUpdate (void) const
 Return the time of the last state update.
const ros::TimelastPoseUpdate (void) const
 Return the time of the last pose update.
void printRobotState (void) const
 Output the current state as ROS INFO.
bool setKinematicStateToTime (const ros::Time &time, planning_models::KinematicState &state) const
void setStateValuesFromCurrentValues (planning_models::KinematicState &state) const
 Sets the model used for collision/valditity checking to the current state values.
void startStateMonitor (void)
 Start the state monitor. By default, the monitor is started after creation.
void stopStateMonitor (void)
 Stop the state monitor.
void waitForState (void) const
 Wait until a full joint state is received (including pose, if pose inclusion is enabled)
virtual ~KinematicModelStateMonitor (void)

Protected Member Functions

void jointStateCallback (const sensor_msgs::JointStateConstPtr &joint_state)
void setupRSM (void)

Protected Attributes

std::map< std::string, double > current_joint_state_map_
boost::recursive_mutex current_joint_values_lock_
bool have_joint_state_
bool have_pose_
double joint_state_cache_allowed_difference_
double joint_state_cache_time_
std::list< std::pair
< ros::Time, std::map
< std::string, double > > > 
joint_state_map_cache_
ros::Subscriber joint_state_subscriber_
const
planning_models::KinematicModel
kmodel_
ros::Time last_joint_state_update_
std::map< std::string, ros::Timelast_joint_update_
ros::Time last_pose_update_
ros::NodeHandle nh_
boost::function< void(const
sensor_msgs::JointStateConstPtr
&joint_state)> 
on_state_update_callback_
tf::Pose pose_
bool printed_out_of_date_
RobotModelsrm_
std::string robot_frame_
ros::NodeHandle root_handle_
bool state_monitor_started_
tf::TransformListenertf_

Detailed Description

KinematicModelStateMonitor is a class that monitors the robot state for the kinematic model defined in RobotModels If the pose is not included, the robot state is the frame of the link it attaches to the world. If the pose is included, the frame of the robot is the one in which the pose is published.

Definition at line 62 of file kinematic_model_state_monitor.h.


Constructor & Destructor Documentation

Definition at line 66 of file kinematic_model_state_monitor.h.

Definition at line 73 of file kinematic_model_state_monitor.h.


Member Function Documentation

void planning_environment::KinematicModelStateMonitor::addOnStateUpdateCallback ( const boost::function< void(const sensor_msgs::JointStateConstPtr &joint_state)> &  callback) [inline]

Definition at line 89 of file kinematic_model_state_monitor.h.

Definition at line 226 of file kinematic_model_state_monitor.cpp.

bool planning_environment::KinematicModelStateMonitor::getCachedJointStateValues ( const ros::Time time,
std::map< std::string, double > &  ret_map 
) const

Definition at line 277 of file kinematic_model_state_monitor.cpp.

std::map<std::string, double> planning_environment::KinematicModelStateMonitor::getCurrentJointStateValues ( ) const [inline]

Definition at line 156 of file kinematic_model_state_monitor.h.

Definition at line 258 of file kinematic_model_state_monitor.cpp.

Get the kinematic model that is being used to check for validity.

Definition at line 94 of file kinematic_model_state_monitor.h.

Get the instance of RobotModels that is being used.

Definition at line 100 of file kinematic_model_state_monitor.h.

Return the transform listener.

Definition at line 106 of file kinematic_model_state_monitor.h.

Return true if a full joint state has been received (including pose, if pose inclusion is enabled)

Definition at line 112 of file kinematic_model_state_monitor.h.

Return true if a joint state has been received in the last sec seconds. If sec < 10us, this function always returns true.

Definition at line 349 of file kinematic_model_state_monitor.cpp.

Return true if a pose has been received in the last sec seconds. If sec < 10us, this function always returns true.

Definition at line 379 of file kinematic_model_state_monitor.cpp.

Check if the state monitor is currently started.

Definition at line 84 of file kinematic_model_state_monitor.h.

Definition at line 93 of file kinematic_model_state_monitor.cpp.

Return the time of the last state update.

Definition at line 118 of file kinematic_model_state_monitor.h.

Return the time of the last pose update.

Definition at line 124 of file kinematic_model_state_monitor.h.

Output the current state as ROS INFO.

Definition at line 266 of file kinematic_model_state_monitor.cpp.

Sets the model used for collision/valditity checking to the current state values.

Definition at line 250 of file kinematic_model_state_monitor.cpp.

Author:
Ioan Sucan

Definition at line 43 of file kinematic_model_state_monitor.cpp.

Start the state monitor. By default, the monitor is started after creation.

Definition at line 65 of file kinematic_model_state_monitor.cpp.

Stop the state monitor.

Definition at line 79 of file kinematic_model_state_monitor.cpp.

Wait until a full joint state is received (including pose, if pose inclusion is enabled)

Definition at line 330 of file kinematic_model_state_monitor.cpp.


Member Data Documentation

Definition at line 171 of file kinematic_model_state_monitor.h.

Definition at line 173 of file kinematic_model_state_monitor.h.

Definition at line 196 of file kinematic_model_state_monitor.h.

Definition at line 195 of file kinematic_model_state_monitor.h.

Definition at line 176 of file kinematic_model_state_monitor.h.

Definition at line 175 of file kinematic_model_state_monitor.h.

std::list<std::pair<ros::Time, std::map<std::string, double> > > planning_environment::KinematicModelStateMonitor::joint_state_map_cache_ [protected]

Definition at line 168 of file kinematic_model_state_monitor.h.

Definition at line 187 of file kinematic_model_state_monitor.h.

Definition at line 180 of file kinematic_model_state_monitor.h.

Definition at line 197 of file kinematic_model_state_monitor.h.

Definition at line 170 of file kinematic_model_state_monitor.h.

Definition at line 198 of file kinematic_model_state_monitor.h.

Definition at line 185 of file kinematic_model_state_monitor.h.

Definition at line 193 of file kinematic_model_state_monitor.h.

Definition at line 190 of file kinematic_model_state_monitor.h.

Definition at line 183 of file kinematic_model_state_monitor.h.

Definition at line 178 of file kinematic_model_state_monitor.h.

Definition at line 191 of file kinematic_model_state_monitor.h.

Definition at line 186 of file kinematic_model_state_monitor.h.

Definition at line 182 of file kinematic_model_state_monitor.h.

Definition at line 188 of file kinematic_model_state_monitor.h.


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


planning_environment
Author(s): Ioan Sucan
autogenerated on Thu Dec 12 2013 11:09:24