#include <robot_state_publisher.h>
Classes | |
| class | empty_tree_exception |
| class | JointState |
Public Member Functions | |
| bool | publishTransforms (std::map< std::string, RobotStatePublisher::JointState > &joint_positions, const ros::Time &time, const ros::Time &republish_time) |
| RobotStatePublisher (const KDL::Tree &tree) | |
| ~RobotStatePublisher () | |
Private Member Functions | |
| void | addChildTransforms (std::map< std::string, RobotStatePublisher::JointState > &joint_positions, const KDL::SegmentMap::const_iterator segment, int &tf_index, const ros::Time &time, const ros::Time &republish_time) |
Private Attributes | |
| robot_state_chain_publisher::RobotStatePublisher::empty_tree_exception | empty_tree_ex |
| bool | ignore_root |
| ros::NodeHandle | n_ |
| std::string | root_ |
| tf::tfMessage | tf_msg_ |
| std::string | tf_prefix_ |
| ros::Publisher | tf_publisher_ |
| KDL::Tree | tree_ |
Definition at line 47 of file robot_state_publisher.h.
Definition at line 49 of file robot_state_publisher.cpp.
Definition at line 51 of file robot_state_publisher.h.
| void robot_state_chain_publisher::RobotStatePublisher::addChildTransforms | ( | std::map< std::string, RobotStatePublisher::JointState > & | joint_positions, |
| const KDL::SegmentMap::const_iterator | segment, | ||
| int & | tf_index, | ||
| const ros::Time & | time, | ||
| const ros::Time & | republish_time | ||
| ) | [private] |
Definition at line 91 of file robot_state_publisher.cpp.
| bool robot_state_chain_publisher::RobotStatePublisher::publishTransforms | ( | std::map< std::string, RobotStatePublisher::JointState > & | joint_positions, |
| const ros::Time & | time, | ||
| const ros::Time & | republish_time | ||
| ) |
robot_state_chain_publisher::RobotStatePublisher::empty_tree_exception robot_state_chain_publisher::RobotStatePublisher::empty_tree_ex [private] |
Definition at line 67 of file robot_state_publisher.h.
Definition at line 63 of file robot_state_publisher.h.
std::string robot_state_chain_publisher::RobotStatePublisher::root_ [private] |
Definition at line 66 of file robot_state_publisher.h.
Definition at line 69 of file robot_state_publisher.h.
std::string robot_state_chain_publisher::RobotStatePublisher::tf_prefix_ [private] |
Definition at line 68 of file robot_state_publisher.h.
Definition at line 64 of file robot_state_publisher.h.
Definition at line 65 of file robot_state_publisher.h.