#include <joint_state_listener.h>
Definition at line 89 of file joint_state_listener.h.
◆ JointStateListener() [1/3]
JointStateListener::JointStateListener |
( |
| ) |
|
◆ JointStateListener() [2/3]
Constructor
- Parameters
-
tree | The kinematic model of a robot, represented by a KDL Tree |
Definition at line 55 of file joint_state_listener.cpp.
◆ JointStateListener() [3/3]
◆ ~JointStateListener()
JointStateListener::~JointStateListener |
( |
| ) |
|
◆ callbackFixedJoint()
◆ callbackJointState()
◆ getTFPrefix()
std::string JointStateListener::getTFPrefix |
( |
| ) |
|
|
private |
◆ ignore_timestamp_
bool robot_state_publisher::JointStateListener::ignore_timestamp_ |
|
protected |
◆ joint_state_sub_
ros::Subscriber robot_state_publisher::JointStateListener::joint_state_sub_ |
|
protected |
◆ last_callback_time_
ros::Time robot_state_publisher::JointStateListener::last_callback_time_ |
|
protected |
◆ last_publish_time_
std::map<std::string, ros::Time> robot_state_publisher::JointStateListener::last_publish_time_ |
|
protected |
◆ mimic_
MimicMap robot_state_publisher::JointStateListener::mimic_ |
|
protected |
◆ publish_interval_
ros::Duration robot_state_publisher::JointStateListener::publish_interval_ |
|
protected |
◆ state_publisher_
std::shared_ptr<RobotStatePublisher> robot_state_publisher::JointStateListener::state_publisher_ |
|
protected |
◆ timer_
ros::Timer robot_state_publisher::JointStateListener::timer_ |
|
protected |
◆ use_tf_static_
bool robot_state_publisher::JointStateListener::use_tf_static_ |
|
protected |
The documentation for this class was generated from the following files: