32 #ifndef TF2_ROS_BUFFER_INTERFACE_H
33 #define TF2_ROS_BUFFER_INTERFACE_H
38 #include <geometry_msgs/TransformStamped.h>
62 virtual geometry_msgs::TransformStamped
63 lookupTransform(
const std::string& target_frame,
const std::string& source_frame,
78 virtual geometry_msgs::TransformStamped
80 const std::string& source_frame,
const ros::Time& source_time,
81 const std::string& fixed_frame,
const ros::Duration timeout)
const = 0;
93 canTransform(
const std::string& target_frame,
const std::string& source_frame,
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;
147 return transform(in, out, target_frame, timeout);
167 template <
class A,
class B>
171 A copy =
transform(in, target_frame, timeout);
193 const std::string& target_frame,
const ros::Time& target_time,
199 fixed_frame, timeout));
221 const std::string& target_frame,
const ros::Time& target_time,
225 return transform(in, out, target_frame, target_time, fixed_frame, timeout);
250 template <
class A,
class B>
252 const std::string& target_frame,
const ros::Time& target_time,
256 A copy =
transform(in, target_frame, target_time, fixed_frame, timeout);
267 #endif // TF2_ROS_BUFFER_INTERFACE_H