#include <joint_state_listener.h>
Public Member Functions | |
JointStateListener (const KDL::Tree &tree, const MimicMap &m, const urdf::Model &model=urdf::Model()) | |
~JointStateListener () | |
Destructor. More... | |
Protected Member Functions | |
virtual void | callbackFixedJoint (const ros::TimerEvent &e) |
virtual void | callbackJointState (const JointStateConstPtr &state) |
Protected Attributes | |
bool | ignore_timestamp_ |
Subscriber | joint_state_sub_ |
ros::Time | last_callback_time_ |
std::map< std::string, ros::Time > | last_publish_time_ |
MimicMap | mimic_ |
Duration | publish_interval_ |
robot_state_publisher::RobotStatePublisher | state_publisher_ |
std::string | tf_prefix_ |
ros::Timer | timer_ |
bool | use_tf_static_ |
Definition at line 56 of file joint_state_listener.h.
JointStateListener::JointStateListener | ( | const KDL::Tree & | tree, |
const MimicMap & | m, | ||
const urdf::Model & | model = urdf::Model() |
||
) |
Constructor
tree | The kinematic model of a robot, represented by a KDL Tree |
Definition at line 50 of file joint_state_listener.cpp.
JointStateListener::~JointStateListener | ( | ) |
Destructor.
Definition at line 83 of file joint_state_listener.cpp.
|
protectedvirtual |
Definition at line 87 of file joint_state_listener.cpp.
|
protectedvirtual |
Definition at line 93 of file joint_state_listener.cpp.
|
protected |
Definition at line 79 of file joint_state_listener.h.
|
protected |
Definition at line 73 of file joint_state_listener.h.
|
protected |
Definition at line 75 of file joint_state_listener.h.
|
protected |
Definition at line 76 of file joint_state_listener.h.
|
protected |
Definition at line 77 of file joint_state_listener.h.
|
protected |
Definition at line 71 of file joint_state_listener.h.
|
protected |
Definition at line 72 of file joint_state_listener.h.
|
protected |
Definition at line 70 of file joint_state_listener.h.
|
protected |
Definition at line 74 of file joint_state_listener.h.
|
protected |
Definition at line 78 of file joint_state_listener.h.