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 #include "robot_state_publisher/robot_state_publisher.h"
00038 #include <kdl/frames_io.hpp>
00039 #include <tf_conversions/tf_kdl.h>
00040
00041 using namespace std;
00042 using namespace ros;
00043
00044
00045
00046 namespace robot_state_publisher{
00047
00048 RobotStatePublisher::RobotStatePublisher(const KDL::Tree& tree)
00049 {
00050
00051 addChildren(tree.getRootSegment());
00052 }
00053
00054
00055
00056 void RobotStatePublisher::addChildren(const KDL::SegmentMap::const_iterator segment)
00057 {
00058 const std::string& root = GetTreeElementSegment(segment->second).getName();
00059
00060 const std::vector<KDL::SegmentMap::const_iterator>& children = GetTreeElementChildren(segment->second);
00061 for (unsigned int i=0; i<children.size(); i++){
00062 const KDL::Segment& child = GetTreeElementSegment(children[i]->second);
00063 SegmentPair s(GetTreeElementSegment(children[i]->second), root, child.getName());
00064 if (child.getJoint().getType() == KDL::Joint::None){
00065 segments_fixed_.insert(make_pair(child.getJoint().getName(), s));
00066 ROS_DEBUG("Adding fixed segment from %s to %s", root.c_str(), child.getName().c_str());
00067 }
00068 else{
00069 segments_.insert(make_pair(child.getJoint().getName(), s));
00070 ROS_DEBUG("Adding moving segment from %s to %s", root.c_str(), child.getName().c_str());
00071 }
00072 addChildren(children[i]);
00073 }
00074 }
00075
00076
00077
00078 void RobotStatePublisher::publishTransforms(const map<string, double>& joint_positions, const Time& time, const std::string& tf_prefix)
00079 {
00080 ROS_DEBUG("Publishing transforms for moving joints");
00081 std::vector<tf::StampedTransform> tf_transforms;
00082 tf::StampedTransform tf_transform;
00083 tf_transform.stamp_ = time;
00084
00085
00086 for (map<string, double>::const_iterator jnt=joint_positions.begin(); jnt != joint_positions.end(); jnt++){
00087 std::map<std::string, SegmentPair>::const_iterator seg = segments_.find(jnt->first);
00088 if (seg != segments_.end()){
00089 tf::transformKDLToTF(seg->second.segment.pose(jnt->second), tf_transform);
00090 tf_transform.frame_id_ = tf::resolve(tf_prefix, seg->second.root);
00091 tf_transform.child_frame_id_ = tf::resolve(tf_prefix, seg->second.tip);
00092 tf_transforms.push_back(tf_transform);
00093 }
00094 }
00095 tf_broadcaster_.sendTransform(tf_transforms);
00096 }
00097
00098
00099
00100 void RobotStatePublisher::publishFixedTransforms(const std::string& tf_prefix)
00101 {
00102 ROS_DEBUG("Publishing transforms for fixed joints");
00103 std::vector<tf::StampedTransform> tf_transforms;
00104 tf::StampedTransform tf_transform;
00105 tf_transform.stamp_ = ros::Time::now()+ros::Duration(0.5);
00106
00107
00108 for (map<string, SegmentPair>::const_iterator seg=segments_fixed_.begin(); seg != segments_fixed_.end(); seg++){
00109 tf::transformKDLToTF(seg->second.segment.pose(0), tf_transform);
00110 tf_transform.frame_id_ = tf::resolve(tf_prefix, seg->second.root);
00111 tf_transform.child_frame_id_ = tf::resolve(tf_prefix, seg->second.tip);
00112 tf_transforms.push_back(tf_transform);
00113 }
00114 tf_broadcaster_.sendTransform(tf_transforms);
00115 }
00116
00117 }
00118
00119
00120