$search
00001 /* (C) 2011 Ruben Smits, ruben.smits@mech.kuleuven.be, Department of Mechanical 00002 * Engineering, Katholieke Universiteit Leuven, Belgium. 00003 * 00004 * This library is free software; you can redistribute it and/or 00005 * modify it under the terms of the GNU Lesser General Public 00006 * License as published by the Free Software Foundation; either 00007 * version 2.1 of the License, or (at your option) any later version. 00008 * 00009 * This library is distributed in the hope that it will be useful, 00010 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00011 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 00012 * Lesser General Public License for more details. 00013 * 00014 * You should have received a copy of the GNU Lesser General Public 00015 * License along with this library; if not, write to the Free Software 00016 * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 00017 */ 00018 00019 /* 00020 * Copyright (c) 2008, Willow Garage, Inc. 00021 * All rights reserved. 00022 * 00023 * Redistribution and use in source and binary forms, with or without 00024 * modification, are permitted provided that the following conditions are met: 00025 * 00026 * * Redistributions of source code must retain the above copyright 00027 * notice, this list of conditions and the following disclaimer. 00028 * * Redistributions in binary form must reproduce the above copyright 00029 * notice, this list of conditions and the following disclaimer in the 00030 * documentation and/or other materials provided with the distribution. 00031 * * Neither the name of the Willow Garage, Inc. nor the names of its 00032 * contributors may be used to endorse or promote products derived from 00033 * this software without specific prior written permission. 00034 * 00035 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00036 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00037 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00038 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00039 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00040 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00041 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00042 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00043 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00044 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00045 * POSSIBILITY OF SUCH DAMAGE. 00046 */ 00047 00048 #include "rtt_tf-component.hpp" 00049 #include <rtt/Component.hpp> 00050 #include <ros/ros.h> 00051 00052 namespace rtt_tf 00053 { 00054 00055 using namespace RTT; 00056 using namespace tf; 00057 00058 RTT_TF::RTT_TF(const std::string& name) : 00059 TaskContext(name, PreOperational), 00060 tf::Transformer(true, ros::Duration(Transformer::DEFAULT_CACHE_TIME)), 00061 prop_interpolating(true), 00062 prop_cache_time(Transformer::DEFAULT_CACHE_TIME), 00063 prop_buffer_size(DEFAULT_BUFFER_SIZE) 00064 { 00065 this->addProperty("interpolating", prop_interpolating); 00066 this->addProperty("cache_time", prop_cache_time); 00067 this->addProperty("buffer_size", prop_buffer_size); 00068 this->addProperty("tf_prefix", prop_tf_prefix); 00069 this->addEventPort("tf_in", port_tf_in); 00070 this->addPort("tf_out", port_tf_out); 00071 00072 this->addOperation("lookupTransform", &RTT_TF::lookupTransformService, this) 00073 .doc("lookup the most recent transform from source to target") 00074 .arg("target", "target frame") 00075 .arg("source", "source frame"); 00076 00077 this->addOperation("lookupTransformAtTime", &RTT_TF::lookupTransformAtTimeService, this) 00078 .doc("lookup the most recent transform from source to target") 00079 .arg("target", "target frame") 00080 .arg("source", "source frame") 00081 .arg("common_time", "common time at which the transform should be computed"); 00082 00083 this->addOperation("broadcastTransform", &RTT_TF::broadcastTransformService, this, RTT::OwnThread) 00084 .doc("lookup the most recent transform from source to target") 00085 .arg("stamped transform", "geometry_msgs::TransformStamped"); 00086 00087 this->provides("tf")->addOperation("lookupTransform", &RTT_TF::lookupTransformService, this) 00088 .doc("lookup the most recent transform from source to target") 00089 .arg("target", "target frame") 00090 .arg("source", "source frame"); 00091 00092 this->provides("tf")->addOperation("lookupTransformAtTime", &RTT_TF::lookupTransformAtTimeService, this) 00093 .doc("lookup the most recent transform from source to target") 00094 .arg("target", "target frame") 00095 .arg("source", "source frame") 00096 .arg("common_time", "common time at which the transform should be computed"); 00097 00098 this->provides("tf")->addOperation("broadcastTransform", &RTT_TF::broadcastTransformService, this, RTT::OwnThread) 00099 .doc("lookup the most recent transform from source to target") 00100 .arg("stamped transform", "geometry_msgs::TransformStamped"); 00101 } 00102 00103 bool RTT_TF::configureHook() 00104 { 00105 Logger::In(this->getName()); 00106 00107 // Get tf prefix rosparam 00108 ros::NodeHandle nh("~"); 00109 std::string tf_prefix_param_key; 00110 if(nh.searchParam("tf_prefix",tf_prefix_param_key)) { 00111 nh.getParam(tf_prefix_param_key, prop_tf_prefix); 00112 } 00113 00114 // Update tf::Transformer configuration 00115 interpolating = prop_interpolating; 00116 cache_time = ros::Duration(prop_cache_time); 00117 00118 // Update the tf::Transformer prefix 00119 tf_prefix_ = prop_tf_prefix; 00120 00121 // Connect to tf topic 00122 ConnPolicy cp = ConnPolicy::buffer(prop_buffer_size); 00123 cp.transport = 3; //3=ROS 00124 cp.name_id = "/tf"; 00125 00126 return (port_tf_in.createStream(cp) && port_tf_out.createStream(cp)); 00127 } 00128 00129 void RTT_TF::updateHook() 00130 { 00131 Logger::In(this->getName()); 00132 #ifndef NDEBUG 00133 log(Debug) << "In update" << endlog(); 00134 #endif 00135 try 00136 { 00137 tf::tfMessage msg_in; 00138 while (port_tf_in.read(msg_in) == NewData) 00139 { 00140 for (unsigned int i = 0; i < msg_in.transforms.size(); i++) 00141 { 00142 StampedTransform trans; 00143 transformStampedMsgToTF(msg_in.transforms[i], trans); 00144 try 00145 { 00146 std::map<std::string, std::string>* msg_header_map = 00147 msg_in.__connection_header.get(); 00148 std::string authority; 00149 std::map<std::string, std::string>::iterator it = 00150 msg_header_map->find("callerid"); 00151 if (it == msg_header_map->end()) 00152 { 00153 log(Warning) << "Message received without callerid" 00154 << endlog(); 00155 authority = "no callerid"; 00156 } 00157 else 00158 { 00159 authority = it->second; 00160 } 00161 this->setTransform(trans, authority); 00162 } catch (TransformException& ex) 00163 { 00164 00165 log(Error) << "Failure to set received transform from " 00166 << msg_in.transforms[i].child_frame_id << " to " 00167 << msg_in.transforms[i].header.frame_id 00168 << " with error: " << ex.what() << endlog(); 00169 } 00170 } 00171 } 00172 00173 } catch (std::exception& ex) 00174 { 00175 log(Error) << ex.what() << endlog(); 00176 } 00177 } 00178 00179 geometry_msgs::TransformStamped RTT_TF::lookupTransformService( 00180 const std::string& target, 00181 const std::string& source) 00182 { 00183 tf::StampedTransform stamped_tf; 00184 ros::Time common_time; 00185 this->getLatestCommonTime(source, target, common_time,NULL); 00186 this->lookupTransform(target, source, common_time, stamped_tf); 00187 geometry_msgs::TransformStamped msg; 00188 tf::transformStampedTFToMsg(stamped_tf,msg); 00189 return msg; 00190 } 00191 00192 geometry_msgs::TransformStamped RTT_TF::lookupTransformAtTimeService( 00193 const std::string& target, 00194 const std::string& source, 00195 const ros::Time& common_time) 00196 { 00197 tf::StampedTransform stamped_tf; 00198 this->lookupTransform(target, source, common_time, stamped_tf); 00199 geometry_msgs::TransformStamped msg; 00200 tf::transformStampedTFToMsg(stamped_tf,msg); 00201 return msg; 00202 } 00203 00204 void RTT_TF::broadcastTransformService( 00205 const geometry_msgs::TransformStamped &tform) 00206 { 00207 // Populate the TF message 00208 tf::tfMessage msg_out; 00209 msg_out.transforms.push_back(tform); 00210 00211 // Resolve names 00212 msg_out.transforms.back().header.frame_id = tf::resolve(prop_tf_prefix, msg_out.transforms.back().header.frame_id); 00213 msg_out.transforms.back().child_frame_id = tf::resolve(prop_tf_prefix, msg_out.transforms.back().child_frame_id); 00214 00215 port_tf_out.write(msg_out); 00216 } 00217 00218 }//namespace 00219 00220 /* 00221 * Using this macro, only one component may live 00222 * in one library *and* you may *not* link this library 00223 * with another component library. Use 00224 * ORO_CREATE_COMPONENT_TYPE() 00225 * ORO_LIST_COMPONENT_TYPE(Rtt_tf) 00226 * In case you want to link with another library that 00227 * already contains components. 00228 * 00229 * If you have put your component class 00230 * in a namespace, don't forget to add it here too: 00231 */ 00232 ORO_CREATE_COMPONENT(rtt_tf::RTT_TF)