#include <joint_state_monitor.h>
Public Member Functions | |
sensor_msgs::JointState | getJointState () |
sensor_msgs::JointState | getJointState (std::vector< std::string > names) |
sensor_msgs::JointState | getJointStateRealJoints () |
JointStateMonitor () | |
void | stop (void) |
Public Attributes | |
bool | active_ |
ros::Time | last_update_ |
Private Member Functions | |
void | jointStateCallback (const sensor_msgs::JointStateConstPtr &joint_state) |
Private Attributes | |
bool | first_time_ |
std::vector< int > | joint_real_state_index_ |
sensor_msgs::JointState | joint_state_ |
std::map< std::string, int > | joint_state_index_ |
ros::Subscriber | joint_state_subscriber_ |
urdf::Model | robot_model_ |
ros::NodeHandle | root_handle_ |
bool | state_monitor_started_ |
boost::mutex | state_mutex_ |
Definition at line 55 of file joint_state_monitor.h.
Definition at line 41 of file joint_state_monitor.cpp.
sensor_msgs::JointState planning_environment::JointStateMonitor::getJointState | ( | ) |
Definition at line 109 of file joint_state_monitor.cpp.
sensor_msgs::JointState planning_environment::JointStateMonitor::getJointState | ( | std::vector< std::string > | names | ) |
Definition at line 137 of file joint_state_monitor.cpp.
sensor_msgs::JointState planning_environment::JointStateMonitor::getJointStateRealJoints | ( | ) |
Definition at line 115 of file joint_state_monitor.cpp.
void planning_environment::JointStateMonitor::jointStateCallback | ( | const sensor_msgs::JointStateConstPtr & | joint_state | ) | [private] |
Definition at line 69 of file joint_state_monitor.cpp.
void planning_environment::JointStateMonitor::stop | ( | void | ) |
Definition at line 61 of file joint_state_monitor.cpp.
Definition at line 65 of file joint_state_monitor.h.
Definition at line 70 of file joint_state_monitor.h.
Definition at line 76 of file joint_state_monitor.h.
sensor_msgs::JointState planning_environment::JointStateMonitor::joint_state_ [private] |
Definition at line 71 of file joint_state_monitor.h.
std::map<std::string,int> planning_environment::JointStateMonitor::joint_state_index_ [private] |
Definition at line 72 of file joint_state_monitor.h.
Definition at line 68 of file joint_state_monitor.h.
Definition at line 64 of file joint_state_monitor.h.
Definition at line 77 of file joint_state_monitor.h.
Definition at line 75 of file joint_state_monitor.h.
Definition at line 69 of file joint_state_monitor.h.
boost::mutex planning_environment::JointStateMonitor::state_mutex_ [private] |
Definition at line 74 of file joint_state_monitor.h.