robot_state_publisher.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Wim Meeussen */
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   // walk the tree and add segments to segments_
00052   addChildren(tree.getRootSegment());
00053 }
00054 
00055 // add children to correct maps
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 // publish moving transforms
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   // loop over all joints
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 // publish fixed transforms
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   // loop over all fixed segments
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 }


robot_state_publisher
Author(s): Ioan Sucan , Jackie Kay , Wim Meeussen
autogenerated on Sat Feb 9 2019 04:16:45