32 #ifndef TF2_ROS__BUFFER_INTERFACE_H_
33 #define TF2_ROS__BUFFER_INTERFACE_H_
36 #include <tf2/transform_datatypes.h>
37 #include <tf2/exceptions.h>
38 #include <tf2/convert.h>
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>
55 inline builtin_interfaces::msg::Time
toMsg(
const tf2::TimePoint & t)
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);
67 inline tf2::TimePoint
fromMsg(
const builtin_interfaces::msg::Time & time_msg)
69 int64_t d = time_msg.sec * 1000000000ull + time_msg.nanosec;
71 return tf2::TimePoint(std::chrono::duration_cast<tf2::Duration>(ns));
74 inline builtin_interfaces::msg::Duration
toMsg(
const tf2::Duration & t)
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);
86 inline tf2::Duration
fromMsg(
const builtin_interfaces::msg::Duration & duration_msg)
88 int64_t d = duration_msg.sec * 1000000000ull + duration_msg.nanosec;
90 return tf2::Duration(std::chrono::duration_cast<tf2::Duration>(ns));
93 inline double timeToSec(
const builtin_interfaces::msg::Time & time_msg)
107 inline rclcpp::Time
toRclcpp(
const tf2::TimePoint & time)
114 inline tf2::Duration
fromRclcpp(
const rclcpp::Duration & duration)
119 inline rclcpp::Duration
toRclcpp(
const tf2::Duration & duration)
121 return rclcpp::Duration(std::chrono::duration_cast<std::chrono::nanoseconds>(duration));
141 virtual geometry_msgs::msg::TransformStamped
144 const tf2::TimePoint & time,
const tf2::Duration timeout)
const = 0;
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;
178 const tf2::TimePoint & time,
const tf2::Duration timeout,
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,
212 const T & in, T & out,
213 const std::string & target_frame, tf2::Duration timeout = tf2::durationFromSec(0.0))
const
217 in, out,
lookupTransform(target_frame, tf2::getFrameId(in), tf2::getTimestamp(in), timeout));
235 const std::string & target_frame, tf2::Duration timeout = tf2::durationFromSec(0.0))
const
238 return this->
transform(in, out, target_frame, timeout);
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
263 A copy = this->
transform(in, target_frame, timeout);
264 tf2::convert(copy, out);
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
292 target_frame, target_time,
293 tf2::getFrameId(in), tf2::getTimestamp(in),
294 fixed_frame, timeout));
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
320 return this->
transform(in, out, target_frame, target_time, fixed_frame, timeout);
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
351 A copy = this->
transform(in, target_frame, target_time, fixed_frame, timeout);
352 tf2::convert(copy, out);
363 #endif // TF2_ROS__BUFFER_INTERFACE_H_