$search
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 "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 // walk the tree and add segments to segments_ 00051 addChildren(tree.getRootSegment()); 00052 } 00053 00054 00055 // add children to correct maps 00056 void RobotStatePublisher::addChildren(const KDL::SegmentMap::const_iterator segment) 00057 { 00058 const std::string& root = segment->second.segment.getName(); 00059 00060 const std::vector<KDL::SegmentMap::const_iterator>& children = segment->second.children; 00061 for (unsigned int i=0; i<children.size(); i++){ 00062 const KDL::Segment& child = children[i]->second.segment; 00063 SegmentPair s(children[i]->second.segment, 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 // publish moving transforms 00078 void RobotStatePublisher::publishTransforms(const map<string, double>& joint_positions, const Time& time) 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 // loop over all joints 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_ = seg->second.root; 00091 tf_transform.child_frame_id_ = seg->second.tip; 00092 tf_transforms.push_back(tf_transform); 00093 } 00094 } 00095 tf_broadcaster_.sendTransform(tf_transforms); 00096 } 00097 00098 00099 // publish fixed transforms 00100 void RobotStatePublisher::publishFixedTransforms() 00101 { 00102 ROS_DEBUG("Publishing transforms for moving joints"); 00103 std::vector<tf::StampedTransform> tf_transforms; 00104 tf::StampedTransform tf_transform; 00105 tf_transform.stamp_ = ros::Time::now()+ros::Duration(0.5); // future publish by 0.5 seconds 00106 00107 // loop over all fixed segments 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_ = seg->second.root; 00111 tf_transform.child_frame_id_ = seg->second.tip; 00112 tf_transforms.push_back(tf_transform); 00113 } 00114 tf_broadcaster_.sendTransform(tf_transforms); 00115 } 00116 00117 } 00118 00119 00120