buffer_interface.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*
3  * Copyright (c) 2008, Willow Garage, Inc.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the Willow Garage, Inc. nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  */
30 
33 #ifndef TF2_ROS_BUFFER_INTERFACE_H
34 #define TF2_ROS_BUFFER_INTERFACE_H
35 
36 #include <tf2/buffer_core.h>
37 #include <tf2/transform_datatypes.h>
38 #include <tf2/exceptions.h>
40 #include <sstream>
41 #include <tf2/convert.h>
42 
43 namespace tf2_ros
44 {
45 
49 class BufferInterface
50 {
51 public:
52 
64  lookupTransform(const std::string& target_frame, const std::string& source_frame,
65  const ros::Time& time, const ros::Duration timeout) const = 0;
66 
80  lookupTransform(const std::string& target_frame, const ros::Time& target_time,
81  const std::string& source_frame, const ros::Time& source_time,
82  const std::string& fixed_frame, const ros::Duration timeout) const = 0;
83 
84 
93  virtual bool
94  canTransform(const std::string& target_frame, const std::string& source_frame,
95  const ros::Time& time, const ros::Duration timeout, std::string* errstr = NULL) const = 0;
96 
107  virtual bool
108  canTransform(const std::string& target_frame, const ros::Time& target_time,
109  const std::string& source_frame, const ros::Time& source_time,
110  const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr = NULL) const = 0;
111 
123  template <class T>
124  T& transform(const T& in, T& out,
125  const std::string& target_frame, ros::Duration timeout=ros::Duration(0.0)) const
126  {
127  // do the transform
129  return out;
130  }
131 
143  template <class T>
144  T transform(const T& in,
145  const std::string& target_frame, ros::Duration timeout=ros::Duration(0.0)) const
146  {
147  T out;
148  return transform(in, out, target_frame, timeout);
149  }
150 
168  template <class A, class B>
169  B& transform(const A& in, B& out,
170  const std::string& target_frame, ros::Duration timeout=ros::Duration(0.0)) const
171  {
172  A copy = transform(in, target_frame, timeout);
173  tf2::convert(copy, out);
174  return out;
175  }
176 
192  template <class T>
193  T& transform(const T& in, T& out,
194  const std::string& target_frame, const ros::Time& target_time,
195  const std::string& fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
196  {
197  // do the transform
198  tf2::doTransform(in, out, lookupTransform(target_frame, target_time,
200  fixed_frame, timeout));
201  return out;
202  }
203 
204 
220  template <class T>
221  T transform(const T& in,
222  const std::string& target_frame, const ros::Time& target_time,
223  const std::string& fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
224  {
225  T out;
226  return transform(in, out, target_frame, target_time, fixed_frame, timeout);
227  }
228 
229 
251  template <class A, class B>
252  B& transform(const A& in, B& out,
253  const std::string& target_frame, const ros::Time& target_time,
254  const std::string& fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
255  {
256  // do the transform
257  A copy = transform(in, target_frame, target_time, fixed_frame, timeout);
258  tf2::convert(copy, out);
259  return out;
260  }
261 
262 
263  }; // class
264 
265 
266 } // namespace
267 
268 #endif // TF2_ROS_BUFFER_INTERFACE_H
tf2::getTimestamp
const ros::Time & getTimestamp(const T &t)
Get the timestamp from data.
tf2::convert
void convert(const A &a, B &b)
Definition: convert.h:114
NULL
#define NULL
tf2_ros::BufferInterface::lookupTransform
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const=0
A
tf2_ros
tf2_ros::BufferInterface::transform
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
ros::Time
tf2::doTransform
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
The templated function expected to be able to do a transform.
tf2::getFrameId
const std::string & getFrameId(const T &t)
Get the frame_id from data.
TransformStamped.h
sick_scan_base.h
sick_generic_device_finder.timeout
timeout
Definition: sick_generic_device_finder.py:113
target_frame
std::string target_frame
tf2_ros::BufferInterface::canTransform
virtual bool canTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout, std::string *errstr=NULL) const=0
ros::Duration
geometry_msgs::TransformStamped_
Definition: TransformStamped.h:25


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:07