tf2_ros  master
This package contains the ROS bindings for the tf2 library, for both Python and C++.
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 
36 #include <tf2/transform_datatypes.h>
37 #include <tf2/exceptions.h>
38 #include <tf2/convert.h>
39 
40 #include <builtin_interfaces/msg/duration.hpp>
41 #include <builtin_interfaces/msg/time.hpp>
42 #include <geometry_msgs/msg/transform_stamped.hpp>
43 #include <rclcpp/rclcpp.hpp>
44 
45 #include <chrono>
46 #include <functional>
47 #include <future>
48 #include <string>
49 
50 namespace tf2_ros
51 {
54 
55 inline builtin_interfaces::msg::Time toMsg(const tf2::TimePoint & t)
56 {
58  std::chrono::duration_cast<std::chrono::nanoseconds>(t.time_since_epoch());
60  std::chrono::duration_cast<std::chrono::seconds>(t.time_since_epoch());
61  builtin_interfaces::msg::Time time_msg;
62  time_msg.sec = static_cast<int32_t>(s.count());
63  time_msg.nanosec = static_cast<uint32_t>(ns.count() % 1000000000ull);
64  return time_msg;
65 }
66 
67 inline tf2::TimePoint fromMsg(const builtin_interfaces::msg::Time & time_msg)
68 {
69  int64_t d = time_msg.sec * 1000000000ull + time_msg.nanosec;
71  return tf2::TimePoint(std::chrono::duration_cast<tf2::Duration>(ns));
72 }
73 
74 inline builtin_interfaces::msg::Duration toMsg(const tf2::Duration & t)
75 {
77  std::chrono::duration_cast<std::chrono::nanoseconds>(t);
79  std::chrono::duration_cast<std::chrono::seconds>(t);
80  builtin_interfaces::msg::Duration duration_msg;
81  duration_msg.sec = static_cast<int32_t>(s.count());
82  duration_msg.nanosec = static_cast<uint32_t>(ns.count() % 1000000000ull);
83  return duration_msg;
84 }
85 
86 inline tf2::Duration fromMsg(const builtin_interfaces::msg::Duration & duration_msg)
87 {
88  int64_t d = duration_msg.sec * 1000000000ull + duration_msg.nanosec;
90  return tf2::Duration(std::chrono::duration_cast<tf2::Duration>(ns));
91 }
92 
93 inline double timeToSec(const builtin_interfaces::msg::Time & time_msg)
94 {
95  auto ns = std::chrono::duration<double, std::nano>(time_msg.nanosec);
96  auto s = std::chrono::duration<double>(time_msg.sec);
98 }
99 
100 inline tf2::TimePoint fromRclcpp(const rclcpp::Time & time)
101 {
102  // tf2::TimePoint is a typedef to a system time point, but rclcpp::Time may be ROS time.
103  // Ignore that, and assume the clock used from rclcpp time points is consistent.
104  return tf2::TimePoint(std::chrono::nanoseconds(time.nanoseconds()));
105 }
106 
107 inline rclcpp::Time toRclcpp(const tf2::TimePoint & time)
108 {
109  // tf2::TimePoint is a typedef to a system time point, but rclcpp::Time may be ROS time.
110  // Use whatever the default clock is.
111  return rclcpp::Time(std::chrono::nanoseconds(time.time_since_epoch()).count());
112 }
113 
114 inline tf2::Duration fromRclcpp(const rclcpp::Duration & duration)
115 {
116  return tf2::Duration(std::chrono::nanoseconds(duration.nanoseconds()));
117 }
118 
119 inline rclcpp::Duration toRclcpp(const tf2::Duration & duration)
120 {
121  return rclcpp::Duration(std::chrono::duration_cast<std::chrono::nanoseconds>(duration));
122 }
123 
128 {
129 public:
141  virtual geometry_msgs::msg::TransformStamped
143  const std::string & target_frame, const std::string & source_frame,
144  const tf2::TimePoint & time, const tf2::Duration timeout) const = 0;
145 
159  virtual geometry_msgs::msg::TransformStamped
161  const std::string & target_frame, const tf2::TimePoint & target_time,
162  const std::string & source_frame, const tf2::TimePoint & source_time,
163  const std::string & fixed_frame, const tf2::Duration timeout) const = 0;
164 
165 
175  virtual bool
176  canTransform(
177  const std::string & target_frame, const std::string & source_frame,
178  const tf2::TimePoint & time, const tf2::Duration timeout,
179  std::string * errstr = NULL) const = 0;
180 
192  virtual bool
193  canTransform(
194  const std::string & target_frame, const tf2::TimePoint & target_time,
195  const std::string & source_frame, const tf2::TimePoint & source_time,
196  const std::string & fixed_frame, const tf2::Duration timeout,
197  std::string * errstr = NULL) const = 0;
198 
210  template<class T>
212  const T & in, T & out,
213  const std::string & target_frame, tf2::Duration timeout = tf2::durationFromSec(0.0)) const
214  {
215  // do the transform
216  tf2::doTransform(
217  in, out, lookupTransform(target_frame, tf2::getFrameId(in), tf2::getTimestamp(in), timeout));
218  return out;
219  }
220 
232  template<class T>
234  const T & in,
235  const std::string & target_frame, tf2::Duration timeout = tf2::durationFromSec(0.0)) const
236  {
237  T out;
238  return this->transform(in, out, target_frame, timeout);
239  }
240 
258  template<class A, class B>
260  const A & in, B & out,
261  const std::string & target_frame, tf2::Duration timeout = tf2::durationFromSec(0.0)) const
262  {
263  A copy = this->transform(in, target_frame, timeout);
264  tf2::convert(copy, out);
265  return out;
266  }
267 
283  template<class T>
285  const T & in, T & out,
286  const std::string & target_frame, const tf2::TimePoint & target_time,
287  const std::string & fixed_frame, tf2::Duration timeout = tf2::durationFromSec(0.0)) const
288  {
289  // do the transform
290  tf2::doTransform(
291  in, out, lookupTransform(
292  target_frame, target_time,
293  tf2::getFrameId(in), tf2::getTimestamp(in),
294  fixed_frame, timeout));
295  return out;
296  }
297 
313  template<class T>
315  const T & in,
316  const std::string & target_frame, const tf2::TimePoint & target_time,
317  const std::string & fixed_frame, tf2::Duration timeout = tf2::durationFromSec(0.0)) const
318  {
319  T out;
320  return this->transform(in, out, target_frame, target_time, fixed_frame, timeout);
321  }
322 
344  template<class A, class B>
346  const A & in, B & out,
347  const std::string & target_frame, const tf2::TimePoint & target_time,
348  const std::string & fixed_frame, tf2::Duration timeout = tf2::durationFromSec(0.0)) const
349  {
350  // do the transform
351  A copy = this->transform(in, target_frame, target_time, fixed_frame, timeout);
352  tf2::convert(copy, out);
353  return out;
354  }
355 
357  {
358  }
359 };
360 
361 } // namespace tf2_ros
362 
363 #endif // TF2_ROS__BUFFER_INTERFACE_H_
std::shared_future
std::string
tf2_ros::BufferInterface
Abstract interface for wrapping tf2::BufferCoreInterface in a ROS-based API. Implementations include ...
Definition: buffer_interface.h:127
std::chrono::nanoseconds
tf2_ros::fromRclcpp
tf2::TimePoint fromRclcpp(const rclcpp::Time &time)
Definition: buffer_interface.h:100
std::function
tf2_ros::BufferInterface::transform
T & transform(const T &in, T &out, const std::string &target_frame, tf2::Duration timeout=tf2::durationFromSec(0.0)) const
Transform an input into the target frame. This function is templated and can take as input any valid ...
Definition: buffer_interface.h:211
tf2_ros::toRclcpp
rclcpp::Time toRclcpp(const tf2::TimePoint &time)
Definition: buffer_interface.h:107
tf2_ros
Definition: async_buffer_interface.h:43
tf2_ros::BufferInterface::lookupTransform
virtual TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const tf2::Duration timeout) const =0
Get the transform between two frames by frame ID.
TF2_ROS_PUBLIC
#define TF2_ROS_PUBLIC
Definition: visibility_control.h:58
tf2_ros::BufferInterface::transform
B & transform(const A &in, B &out, const std::string &target_frame, const tf2::TimePoint &target_time, const std::string &fixed_frame, tf2::Duration timeout=tf2::durationFromSec(0.0)) const
Transform an input into the target frame and convert to a specified output type (advanced)....
Definition: buffer_interface.h:345
visibility_control.h
tf2_ros::TransformReadyCallback
std::function< void(const TransformStampedFuture &)> TransformReadyCallback
Definition: async_buffer_interface.h:47
tf2_ros::fromMsg
tf2::TimePoint fromMsg(const builtin_interfaces::msg::Time &time_msg)
Definition: buffer_interface.h:67
tf2_ros::BufferInterface::canTransform
virtual TF2_ROS_PUBLIC bool canTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const tf2::Duration timeout, std::string *errstr=NULL) const =0
Test if a transform is possible.
std::chrono::duration_cast
T duration_cast(T... args)
tf2_ros::BufferInterface::transform
T transform(const T &in, const std::string &target_frame, const tf2::TimePoint &target_time, const std::string &fixed_frame, tf2::Duration timeout=tf2::durationFromSec(0.0)) const
Transform an input into the target frame (advanced). This function is templated and can take as input...
Definition: buffer_interface.h:314
std::chrono::seconds::count
T count(T... args)
tf2_ros::BufferInterface::transform
B & transform(const A &in, B &out, const std::string &target_frame, tf2::Duration timeout=tf2::durationFromSec(0.0)) const
Transform an input into the target frame and convert to a specified output type. It is templated on t...
Definition: buffer_interface.h:259
tf2_ros::BufferInterface::transform
T transform(const T &in, const std::string &target_frame, tf2::Duration timeout=tf2::durationFromSec(0.0)) const
Transform an input into the target frame. This function is templated and can take as input any valid ...
Definition: buffer_interface.h:233
tf2_ros::toMsg
builtin_interfaces::msg::Time toMsg(const tf2::TimePoint &t)
Definition: buffer_interface.h:55
tf2_ros::timeToSec
double timeToSec(const builtin_interfaces::msg::Time &time_msg)
Definition: buffer_interface.h:93
tf2_ros::BufferInterface::transform
T & transform(const T &in, T &out, const std::string &target_frame, const tf2::TimePoint &target_time, const std::string &fixed_frame, tf2::Duration timeout=tf2::durationFromSec(0.0)) const
Transform an input into the target frame (advanced). This function is templated and can take as input...
Definition: buffer_interface.h:284
tf2_ros::BufferInterface::~BufferInterface
virtual ~BufferInterface()
Definition: buffer_interface.h:356
tf2_ros::TransformStampedFuture
std::shared_future< geometry_msgs::msg::TransformStamped > TransformStampedFuture
Definition: async_buffer_interface.h:46