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 T transform(const T &in, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
Transform an input into the target frame (advanced). This function is templated and can take as input...
const std::string & getFrameId(const T &t)
Abstract interface for wrapping tf2::BufferCore in a ROS-based API. Implementations include tf2_ros::...
T & transform(const T &in, T &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
Transform an input into the target frame (advanced). This function is templated and can take as input...
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const =0
Get the transform between two frames by frame ID.
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
T transform(const T &in, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
Transform an input into the target frame. This function is templated and can take as input any valid ...
const ros::Time & getTimestamp(const T &t)
void convert(const A &a, B &b)
T & transform(const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
Transform an input into the target frame. This function is templated and can take as input any valid ...
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout, std::string *errstr=NULL) const =0
Test if a transform is possible.
B & transform(const A &in, B &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
Transform an input into the target frame and convert to a specified output type. It is templated on t...
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
Transform an input into the target frame and convert to a specified output type (advanced). It is templated on two types: the type of the input object and the type of the transformed output. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). The function will calculate the transformation and then convert the result into the specified output type. Compilation will fail if a known conversion does not exist bewteen the two template parameters. This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time.