32 #ifndef TF2_ROS_BUFFER_H 33 #define TF2_ROS_BUFFER_H 37 #include <tf2_msgs/FrameGraph.h> 75 virtual geometry_msgs::TransformStamped
76 lookupTransform(
const std::string& target_frame,
const std::string& source_frame,
91 virtual geometry_msgs::TransformStamped
93 const std::string& source_frame,
const ros::Time& source_time,
94 const std::string& fixed_frame,
const ros::Duration timeout)
const;
106 canTransform(
const std::string& target_frame,
const std::string& source_frame,
121 const std::string& source_frame,
const ros::Time& source_time,
122 const std::string& fixed_frame,
const ros::Duration timeout, std::string* errstr = NULL)
const;
128 bool getFrames(tf2_msgs::FrameGraph::Request& req, tf2_msgs::FrameGraph::Response& res) ;
139 static const std::string
threading_error =
"Do not call canTransform or lookupTransform with a timeout unless you are using another thread for populating data. Without a dedicated thread it will always timeout. If you have a separate thread servicing tf messages, call setUsingDedicatedThread(true) on your Buffer instance.";
144 #endif // TF2_ROS_BUFFER_H
geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time) const
Abstract interface for wrapping tf2::BufferCore in a ROS-based API. Implementations include tf2_ros::...
Standard implementation of the tf2_ros::BufferInterface abstract data type.
static const std::string threading_error
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
Test if a transform is possible.
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
Get the transform between two frames by frame ID.
ros::ServiceServer frames_server_
bool getFrames(tf2_msgs::FrameGraph::Request &req, tf2_msgs::FrameGraph::Response &res)
bool checkAndErrorDedicatedThreadPresent(std::string *errstr) const
Buffer(ros::Duration cache_time=ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug=false)
Constructor for a Buffer object.