$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00032 #ifndef TF2_ROS_BUFFER_INTERFACE_H 00033 #define TF2_ROS_BUFFER_INTERFACE_H 00034 00035 #include <tf2/buffer_core.h> 00036 #include <tf2/transform_datatypes.h> 00037 #include <tf2/exceptions.h> 00038 #include <geometry_msgs/TransformStamped.h> 00039 #include <sstream> 00040 00041 namespace tf2 00042 { 00043 00053 template <class T> 00054 void doTransform(const T& data_in, T& data_out, const geometry_msgs::TransformStamped& transform); 00055 00060 template <class T> 00061 const ros::Time& getTimestamp(const T& t); 00062 00067 template <class T> 00068 const std::string& getFrameId(const T& t); 00069 00070 00071 00072 /* An implementation for Stamped<P> datatypes */ 00073 template <class P> 00074 const ros::Time& getTimestamp(const tf2::Stamped<P>& t) 00075 { 00076 return t.stamp_; 00077 } 00078 00079 /* An implementation for Stamped<P> datatypes */ 00080 template <class P> 00081 const std::string& getFrameId(const tf2::Stamped<P>& t) 00082 { 00083 return t.frame_id_; 00084 } 00085 00086 template <class A, class B> 00087 void convert(const A& a, B& b) 00088 { 00089 //printf("In double type convert\n"); 00090 fromMsg(toMsg(a), b); 00091 } 00092 00093 template <class A> 00094 void convert(const A& a1, A& a2) 00095 { 00096 //printf("In single type convert\n"); 00097 if(&a1 != &a2) 00098 a2 = a1; 00099 } 00100 00101 // extend the TFCore class and the TFCpp class 00102 class BufferInterface 00103 { 00104 public: 00105 00116 virtual geometry_msgs::TransformStamped 00117 lookupTransform(const std::string& target_frame, const std::string& source_frame, 00118 const ros::Time& time, const ros::Duration timeout) const = 0; 00119 00132 virtual geometry_msgs::TransformStamped 00133 lookupTransform(const std::string& target_frame, const ros::Time& target_time, 00134 const std::string& source_frame, const ros::Time& source_time, 00135 const std::string& fixed_frame, const ros::Duration timeout) const = 0; 00136 00137 00146 virtual bool 00147 canTransform(const std::string& target_frame, const std::string& source_frame, 00148 const ros::Time& time, const ros::Duration timeout, std::string* errstr = NULL) const = 0; 00149 00160 virtual bool 00161 canTransform(const std::string& target_frame, const ros::Time& target_time, 00162 const std::string& source_frame, const ros::Time& source_time, 00163 const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr = NULL) const = 0; 00164 00165 // Transform, simple api, with pre-allocation 00166 template <class T> 00167 T& transform(const T& in, T& out, 00168 const std::string& target_frame, ros::Duration timeout=ros::Duration(0.0)) const 00169 { 00170 // do the transform 00171 doTransform(in, out, lookupTransform(target_frame, getFrameId(in), getTimestamp(in), timeout)); 00172 return out; 00173 } 00174 00175 00176 // transform, simple api, no pre-allocation 00177 template <class T> 00178 T transform(const T& in, 00179 const std::string& target_frame, ros::Duration timeout=ros::Duration(0.0)) const 00180 { 00181 T out; 00182 return transform(in, out, target_frame, timeout); 00183 } 00184 00185 //transform, simple api, different types, pre-allocation 00186 template <class A, class B> 00187 B& transform(const A& in, B& out, 00188 const std::string& target_frame, ros::Duration timeout=ros::Duration(0.0)) const 00189 { 00190 A copy = transform(in, target_frame, timeout); 00191 convert(copy, out); 00192 return out; 00193 } 00194 00195 // Transform, advanced api, with pre-allocation 00196 template <class T> 00197 T& transform(const T& in, T& out, 00198 const std::string& target_frame, const ros::Time& target_time, 00199 const std::string& fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const 00200 { 00201 // do the transform 00202 doTransform(in, out, lookupTransform(target_frame, target_time, 00203 getFrameId(in), getTimestamp(in), 00204 fixed_frame, timeout)); 00205 return out; 00206 } 00207 00208 00209 // transform, simple api, no pre-allocation 00210 template <class T> 00211 T& transform(const T& in, 00212 const std::string& target_frame, const ros::Time& target_time, 00213 const std::string& fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const 00214 { 00215 T out; 00216 return transform(in, out, target_frame, target_time, fixed_frame, timeout); 00217 } 00218 00219 // Transform, advanced api, different types, with pre-allocation 00220 template <class A, class B> 00221 B& transform(const A& in, B& out, 00222 const std::string& target_frame, const ros::Time& target_time, 00223 const std::string& fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const 00224 { 00225 // do the transform 00226 A copy = transform(in, target_frame, target_time, fixed_frame, timeout); 00227 convert(copy, out); 00228 return out; 00229 } 00230 00231 00232 }; // class 00233 00234 00235 } // namespace 00236 00237 #endif // TF2_ROS_BUFFER_INTERFACE_H