buffer_interface.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
32 #ifndef TF2_ROS_BUFFER_INTERFACE_H
33 #define TF2_ROS_BUFFER_INTERFACE_H
34 
35 #include <tf2/buffer_core.h>
37 #include <tf2/exceptions.h>
38 #include <geometry_msgs/TransformStamped.h>
39 #include <sstream>
40 #include <tf2/convert.h>
41 
42 namespace tf2_ros
43 {
44 
49 {
50 public:
51 
62  virtual geometry_msgs::TransformStamped
63  lookupTransform(const std::string& target_frame, const std::string& source_frame,
64  const ros::Time& time, const ros::Duration timeout) const = 0;
65 
78  virtual geometry_msgs::TransformStamped
79  lookupTransform(const std::string& target_frame, const ros::Time& target_time,
80  const std::string& source_frame, const ros::Time& source_time,
81  const std::string& fixed_frame, const ros::Duration timeout) const = 0;
82 
83 
92  virtual bool
93  canTransform(const std::string& target_frame, const std::string& source_frame,
94  const ros::Time& time, const ros::Duration timeout, std::string* errstr = NULL) const = 0;
95 
106  virtual bool
107  canTransform(const std::string& target_frame, const ros::Time& target_time,
108  const std::string& source_frame, const ros::Time& source_time,
109  const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr = NULL) const = 0;
110 
122  template <class T>
123  T& transform(const T& in, T& out,
124  const std::string& target_frame, ros::Duration timeout=ros::Duration(0.0)) const
125  {
126  // do the transform
127  tf2::doTransform(in, out, lookupTransform(target_frame, tf2::getFrameId(in), tf2::getTimestamp(in), timeout));
128  return out;
129  }
130 
142  template <class T>
143  T transform(const T& in,
144  const std::string& target_frame, ros::Duration timeout=ros::Duration(0.0)) const
145  {
146  T out;
147  return transform(in, out, target_frame, timeout);
148  }
149 
167  template <class A, class B>
168  B& transform(const A& in, B& out,
169  const std::string& target_frame, ros::Duration timeout=ros::Duration(0.0)) const
170  {
171  A copy = transform(in, target_frame, timeout);
172  tf2::convert(copy, out);
173  return out;
174  }
175 
191  template <class T>
192  T& transform(const T& in, T& out,
193  const std::string& target_frame, const ros::Time& target_time,
194  const std::string& fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
195  {
196  // do the transform
197  tf2::doTransform(in, out, lookupTransform(target_frame, target_time,
199  fixed_frame, timeout));
200  return out;
201  }
202 
203 
219  template <class T>
220  T transform(const T& in,
221  const std::string& target_frame, const ros::Time& target_time,
222  const std::string& fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
223  {
224  T out;
225  return transform(in, out, target_frame, target_time, fixed_frame, timeout);
226  }
227 
228 
250  template <class A, class B>
251  B& transform(const A& in, B& out,
252  const std::string& target_frame, const ros::Time& target_time,
253  const std::string& fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
254  {
255  // do the transform
256  A copy = transform(in, target_frame, target_time, fixed_frame, timeout);
257  tf2::convert(copy, out);
258  return out;
259  }
260 
261 
262  }; // class
263 
264 
265 } // namespace
266 
267 #endif // TF2_ROS_BUFFER_INTERFACE_H
T transform(const T &in, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
Transform an input into the target frame (advanced). This function is templated and can take as input...
const std::string & getFrameId(const T &t)
Abstract interface for wrapping tf2::BufferCore in a ROS-based API. Implementations include tf2_ros::...
T & transform(const T &in, T &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
Transform an input into the target frame (advanced). This function is templated and can take as input...
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const =0
Get the transform between two frames by frame ID.
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
T transform(const T &in, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
Transform an input into the target frame. This function is templated and can take as input any valid ...
Definition: buffer.h:42
const ros::Time & getTimestamp(const T &t)
void convert(const A &a, B &b)
T & transform(const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
Transform an input into the target frame. This function is templated and can take as input any valid ...
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout, std::string *errstr=NULL) const =0
Test if a transform is possible.
B & transform(const A &in, B &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
Transform an input into the target frame and convert to a specified output type. It is templated on t...
B & transform(const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
Transform an input into the target frame and convert to a specified output type (advanced). It is templated on two types: the type of the input object and the type of the transformed output. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). The function will calculate the transformation and then convert the result into the specified output type. Compilation will fail if a known conversion does not exist bewteen the two template parameters. This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time.


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Fri Oct 16 2020 19:08:54