Go to the documentation of this file.
33 #ifndef TF2_ROS_BUFFER_INTERFACE_H
34 #define TF2_ROS_BUFFER_INTERFACE_H
36 #include <tf2/buffer_core.h>
37 #include <tf2/transform_datatypes.h>
38 #include <tf2/exceptions.h>
41 #include <tf2/convert.h>
81 const std::string& source_frame,
const ros::Time& source_time,
109 const std::string& source_frame,
const ros::Time& source_time,
168 template <
class A,
class B>
251 template <
class A,
class B>
268 #endif // TF2_ROS_BUFFER_INTERFACE_H
const ros::Time & getTimestamp(const T &t)
Get the timestamp from data.
void convert(const A &a, B &b)
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const=0
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
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
The templated function expected to be able to do a transform.
const std::string & getFrameId(const T &t)
Get the frame_id from data.
virtual bool canTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout, std::string *errstr=NULL) const=0
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:07