Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef ROBOT_STATE_PUBLISHER_H
00038 #define ROBOT_STATE_PUBLISHER_H
00039
00040 #include <ros/ros.h>
00041 #include <boost/scoped_ptr.hpp>
00042 #include <tf/tf.h>
00043 #include <urdf/model.h>
00044 #include <tf2_ros/static_transform_broadcaster.h>
00045 #include <tf2_ros/transform_broadcaster.h>
00046 #include <kdl/frames.hpp>
00047 #include <kdl/segment.hpp>
00048 #include <kdl/tree.hpp>
00049
00050 namespace robot_state_publisher {
00051
00052 class SegmentPair
00053 {
00054 public:
00055 SegmentPair(const KDL::Segment& p_segment, const std::string& p_root, const std::string& p_tip):
00056 segment(p_segment), root(p_root), tip(p_tip){}
00057
00058 KDL::Segment segment;
00059 std::string root, tip;
00060 };
00061
00062
00063 class RobotStatePublisher
00064 {
00065 public:
00069 RobotStatePublisher(const KDL::Tree& tree, const urdf::Model& model = urdf::Model());
00070
00072 ~RobotStatePublisher(){};
00073
00078 void publishTransforms(const std::map<std::string, double>& joint_positions, const ros::Time& time, const std::string& tf_prefix);
00079 void publishFixedTransforms(const std::string& tf_prefix, bool use_tf_static = false);
00080
00081 private:
00082 void addChildren(const KDL::SegmentMap::const_iterator segment);
00083
00084 std::map<std::string, SegmentPair> segments_, segments_fixed_;
00085 const urdf::Model& model_;
00086 tf2_ros::TransformBroadcaster tf_broadcaster_;
00087 tf2_ros::StaticTransformBroadcaster static_tf_broadcaster_;
00088 };
00089
00090 }
00091
00092 #endif