37 #ifndef ROBOT_STATE_PUBLISHER_H 38 #define ROBOT_STATE_PUBLISHER_H 41 #include <boost/scoped_ptr.hpp> 46 #include <kdl/frames.hpp> 47 #include <kdl/segment.hpp> 48 #include <kdl/tree.hpp> 78 virtual void publishTransforms(
const std::map<std::string, double>& joint_positions,
const ros::Time& time,
const std::string& tf_prefix);
79 virtual void publishFixedTransforms(
const std::string& tf_prefix,
bool use_tf_static =
false);
82 virtual void addChildren(
const KDL::SegmentMap::const_iterator
segment);
~RobotStatePublisher()
Destructor.
std::map< std::string, SegmentPair > segments_fixed_
const urdf::Model & model_
tf2_ros::TransformBroadcaster tf_broadcaster_
SegmentPair(const KDL::Segment &p_segment, const std::string &p_root, const std::string &p_tip)
tf2_ros::StaticTransformBroadcaster static_tf_broadcaster_