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
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
00073 template <class P>
00074 const ros::Time& getTimestamp(const tf2::Stamped<P>& t)
00075 {
00076 return t.stamp_;
00077 }
00078
00079
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
00090 fromMsg(toMsg(a), b);
00091 }
00092
00093 template <class A>
00094 void convert(const A& a1, A& a2)
00095 {
00096
00097 if(&a1 != &a2)
00098 a2 = a1;
00099 }
00100
00101
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
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
00171 doTransform(in, out, lookupTransform(target_frame, getFrameId(in), getTimestamp(in), timeout));
00172 return out;
00173 }
00174
00175
00176
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
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
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
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
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
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
00226 A copy = transform(in, target_frame, target_time, fixed_frame, timeout);
00227 convert(copy, out);
00228 return out;
00229 }
00230
00231
00232 };
00233
00234
00235 }
00236
00237 #endif // TF2_ROS_BUFFER_INTERFACE_H