32 #ifndef TF2_ROS_BUFFER_INTERFACE_H 
   33 #define TF2_ROS_BUFFER_INTERFACE_H 
   35 #include <rclcpp/rclcpp.hpp> 
   37 #include <tf2/transform_datatypes.h> 
   38 #include <tf2/exceptions.h> 
   39 #include <geometry_msgs/msg/transform_stamped.hpp> 
   41 #include <tf2/convert.h> 
   48   inline builtin_interfaces::msg::Time 
toMsg(
const tf2::TimePoint & t)
 
   51       std::chrono::duration_cast<std::chrono::nanoseconds>(t.time_since_epoch());
 
   53       std::chrono::duration_cast<std::chrono::seconds>(t.time_since_epoch());
 
   54     builtin_interfaces::msg::Time time_msg;
 
   55     time_msg.sec = (int32_t)s.
count();
 
   56     time_msg.nanosec = (uint32_t)(ns.
count() % 1000000000ull);
 
   60   inline tf2::TimePoint 
fromMsg(
const builtin_interfaces::msg::Time & time_msg)
 
   62     int64_t d = time_msg.sec * 1000000000ull + time_msg.nanosec;
 
   64     return tf2::TimePoint(std::chrono::duration_cast<tf2::Duration>(ns));
 
   67   inline builtin_interfaces::msg::Duration 
toMsg(
const tf2::Duration & t)
 
   70       std::chrono::duration_cast<std::chrono::nanoseconds>(t);
 
   72       std::chrono::duration_cast<std::chrono::seconds>(t);
 
   73     builtin_interfaces::msg::Duration duration_msg;
 
   74     duration_msg.sec = (int32_t)s.
count();
 
   75     duration_msg.nanosec = (uint32_t)(ns.
count() % 1000000000ull);
 
   79   inline tf2::Duration 
fromMsg(
const builtin_interfaces::msg::Duration & duration_msg)
 
   81     int64_t d = duration_msg.sec * 1000000000ull + duration_msg.nanosec;
 
   83     return tf2::Duration(std::chrono::duration_cast<tf2::Duration>(ns));
 
   86   inline double timeToSec(
const builtin_interfaces::msg::Time & time_msg)
 
   93   inline tf2::TimePoint 
fromRclcpp(
const rclcpp::Time & time)
 
  100   inline rclcpp::Time 
toRclcpp(
const tf2::TimePoint & time)
 
  107   inline tf2::Duration 
fromRclcpp(
const rclcpp::Duration & duration)
 
  112   inline rclcpp::Duration 
toRclcpp(
const tf2::Duration & duration)
 
  114     return rclcpp::Duration(std::chrono::duration_cast<std::chrono::nanoseconds>(duration));
 
  134   virtual geometry_msgs::msg::TransformStamped
 
  136             const tf2::TimePoint& time, 
const tf2::Duration timeout) 
const = 0;
 
  151   virtual geometry_msgs::msg::TransformStamped 
 
  153             const std::string& source_frame, 
const tf2::TimePoint& source_time,
 
  154             const std::string& fixed_frame, 
const tf2::Duration timeout) 
const = 0;
 
  168          const tf2::TimePoint& time, 
const tf2::Duration timeout, 
std::string* errstr = NULL) 
const = 0;
 
  183          const std::string& source_frame, 
const tf2::TimePoint& source_time,
 
  199              const std::string& target_frame, tf2::Duration timeout=tf2::durationFromSec(0.0))
 const 
  202     tf2::doTransform(in, out, 
lookupTransform(target_frame, tf2::getFrameId(in), tf2::getTimestamp(in), timeout));
 
  219             const std::string& target_frame, tf2::Duration timeout=tf2::durationFromSec(0.0))
 const 
  222     return transform(in, out, target_frame, timeout);
 
  242   template <
class A, 
class B>
 
  244         const std::string& target_frame, tf2::Duration timeout=tf2::durationFromSec(0.0))
 const 
  246     A copy = 
transform(in, target_frame, timeout);
 
  247     tf2::convert(copy, out);
 
  268              const std::string& target_frame, 
const tf2::TimePoint& target_time,
 
  269              const std::string& fixed_frame, tf2::Duration timeout=tf2::durationFromSec(0.0))
 const 
  273                                               tf2::getFrameId(in), tf2::getTimestamp(in), 
 
  274                                               fixed_frame, timeout));
 
  295              const std::string& target_frame, 
const tf2::TimePoint& target_time,
 
  296              const std::string& fixed_frame, tf2::Duration timeout=tf2::durationFromSec(0.0))
 const 
  299     return transform(in, out, target_frame, target_time, fixed_frame, timeout);
 
  323   template <
class A, 
class B>
 
  325              const std::string& target_frame, 
const tf2::TimePoint& target_time,
 
  326              const std::string& fixed_frame, tf2::Duration timeout=tf2::durationFromSec(0.0))
 const 
  329     A copy = 
transform(in, target_frame, target_time, fixed_frame, timeout);
 
  330     tf2::convert(copy, out);
 
  342 #endif // TF2_ROS_BUFFER_INTERFACE_H