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 <kdl/frames_io.hpp>
00038 #include <geometry_msgs/TransformStamped.h>
00039 #include <tf2_kdl/tf2_kdl.h>
00040
00041 #include "robot_state_publisher/robot_state_publisher.h"
00042
00043 using namespace std;
00044 using namespace ros;
00045
00046 namespace robot_state_publisher {
00047
00048 RobotStatePublisher::RobotStatePublisher(const KDL::Tree& tree, const urdf::Model& model)
00049 : model_(model)
00050 {
00051
00052 addChildren(tree.getRootSegment());
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 if (model_.getJoint(child.getJoint().getName()) && model_.getJoint(child.getJoint().getName())->type == urdf::Joint::FLOATING) {
00066 ROS_INFO("Floating joint. Not adding segment from %s to %s. This TF can not be published based on joint_states info", root.c_str(), child.getName().c_str());
00067 }
00068 else {
00069 segments_fixed_.insert(make_pair(child.getJoint().getName(), s));
00070 ROS_DEBUG("Adding fixed segment from %s to %s", root.c_str(), child.getName().c_str());
00071 }
00072 }
00073 else {
00074 segments_.insert(make_pair(child.getJoint().getName(), s));
00075 ROS_DEBUG("Adding moving segment from %s to %s", root.c_str(), child.getName().c_str());
00076 }
00077 addChildren(children[i]);
00078 }
00079 }
00080
00081
00082
00083 void RobotStatePublisher::publishTransforms(const map<string, double>& joint_positions, const Time& time, const std::string& tf_prefix)
00084 {
00085 ROS_DEBUG("Publishing transforms for moving joints");
00086 std::vector<geometry_msgs::TransformStamped> tf_transforms;
00087
00088
00089 for (map<string, double>::const_iterator jnt=joint_positions.begin(); jnt != joint_positions.end(); jnt++) {
00090 std::map<std::string, SegmentPair>::const_iterator seg = segments_.find(jnt->first);
00091 if (seg != segments_.end()) {
00092 geometry_msgs::TransformStamped tf_transform = tf2::kdlToTransform(seg->second.segment.pose(jnt->second));
00093 tf_transform.header.stamp = time;
00094 tf_transform.header.frame_id = tf::resolve(tf_prefix, seg->second.root);
00095 tf_transform.child_frame_id = tf::resolve(tf_prefix, seg->second.tip);
00096 tf_transforms.push_back(tf_transform);
00097 }
00098 }
00099 tf_broadcaster_.sendTransform(tf_transforms);
00100 }
00101
00102
00103 void RobotStatePublisher::publishFixedTransforms(const std::string& tf_prefix, bool use_tf_static)
00104 {
00105 ROS_DEBUG("Publishing transforms for fixed joints");
00106 std::vector<geometry_msgs::TransformStamped> tf_transforms;
00107 geometry_msgs::TransformStamped tf_transform;
00108
00109
00110 for (map<string, SegmentPair>::const_iterator seg=segments_fixed_.begin(); seg != segments_fixed_.end(); seg++) {
00111 geometry_msgs::TransformStamped tf_transform = tf2::kdlToTransform(seg->second.segment.pose(0));
00112 tf_transform.header.stamp = ros::Time::now();
00113 if (!use_tf_static) {
00114 tf_transform.header.stamp += ros::Duration(0.5);
00115 }
00116 tf_transform.header.frame_id = tf::resolve(tf_prefix, seg->second.root);
00117 tf_transform.child_frame_id = tf::resolve(tf_prefix, seg->second.tip);
00118 tf_transforms.push_back(tf_transform);
00119 }
00120 if (use_tf_static) {
00121 static_tf_broadcaster_.sendTransform(tf_transforms);
00122 }
00123 else {
00124 tf_broadcaster_.sendTransform(tf_transforms);
00125 }
00126 }
00127
00128 }