#include <robot_state_publisher.h>
Public Member Functions | |
void | publishFixedTransforms (const std::string &tf_prefix, bool use_tf_static=false) |
void | publishTransforms (const std::map< std::string, double > &joint_positions, const ros::Time &time, const std::string &tf_prefix) |
RobotStatePublisher (const KDL::Tree &tree, const urdf::Model &model=urdf::Model()) | |
~RobotStatePublisher () | |
Destructor. | |
Private Member Functions | |
void | addChildren (const KDL::SegmentMap::const_iterator segment) |
Private Attributes | |
const urdf::Model & | model_ |
std::map< std::string, SegmentPair > | segments_ |
std::map< std::string, SegmentPair > | segments_fixed_ |
tf2_ros::StaticTransformBroadcaster | static_tf_broadcaster_ |
tf2_ros::TransformBroadcaster | tf_broadcaster_ |
Definition at line 63 of file robot_state_publisher.h.
robot_state_publisher::RobotStatePublisher::RobotStatePublisher | ( | const KDL::Tree & | tree, |
const urdf::Model & | model = urdf::Model() |
||
) |
Constructor
tree | The kinematic model of a robot, represented by a KDL Tree |
Definition at line 48 of file robot_state_publisher.cpp.
Destructor.
Definition at line 72 of file robot_state_publisher.h.
void robot_state_publisher::RobotStatePublisher::addChildren | ( | const KDL::SegmentMap::const_iterator | segment | ) | [private] |
Definition at line 56 of file robot_state_publisher.cpp.
void robot_state_publisher::RobotStatePublisher::publishFixedTransforms | ( | const std::string & | tf_prefix, |
bool | use_tf_static = false |
||
) |
Definition at line 103 of file robot_state_publisher.cpp.
void robot_state_publisher::RobotStatePublisher::publishTransforms | ( | const std::map< std::string, double > & | joint_positions, |
const ros::Time & | time, | ||
const std::string & | tf_prefix | ||
) |
Publish transforms to tf
joint_positions | A map of joint names and joint positions. |
time | The time at which the joint positions were recorded |
Definition at line 83 of file robot_state_publisher.cpp.
const urdf::Model& robot_state_publisher::RobotStatePublisher::model_ [private] |
Definition at line 85 of file robot_state_publisher.h.
std::map<std::string, SegmentPair> robot_state_publisher::RobotStatePublisher::segments_ [private] |
Definition at line 84 of file robot_state_publisher.h.
std::map<std::string, SegmentPair> robot_state_publisher::RobotStatePublisher::segments_fixed_ [private] |
Definition at line 84 of file robot_state_publisher.h.
tf2_ros::StaticTransformBroadcaster robot_state_publisher::RobotStatePublisher::static_tf_broadcaster_ [private] |
Definition at line 87 of file robot_state_publisher.h.
Definition at line 86 of file robot_state_publisher.h.