Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00032 #ifndef TF2_ROS_BUFFER_H
00033 #define TF2_ROS_BUFFER_H
00034
00035 #include <tf2_ros/buffer_interface.h>
00036 #include <tf2/buffer_core.h>
00037 #include <tf2_msgs/FrameGraph.h>
00038 #include <ros/ros.h>
00039 #include <tf2/convert.h>
00040
00041
00042 namespace tf2_ros
00043 {
00044
00045
00046 class Buffer: public BufferInterface, public tf2::BufferCore
00047 {
00048 public:
00049 using tf2::BufferCore::lookupTransform;
00050 using tf2::BufferCore::canTransform;
00051
00058 Buffer(ros::Duration cache_time = ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug = false);
00059
00070 virtual geometry_msgs::TransformStamped
00071 lookupTransform(const std::string& target_frame, const std::string& source_frame,
00072 const ros::Time& time, const ros::Duration timeout) const;
00073
00086 virtual geometry_msgs::TransformStamped
00087 lookupTransform(const std::string& target_frame, const ros::Time& target_time,
00088 const std::string& source_frame, const ros::Time& source_time,
00089 const std::string& fixed_frame, const ros::Duration timeout) const;
00090
00091
00100 virtual bool
00101 canTransform(const std::string& target_frame, const std::string& source_frame,
00102 const ros::Time& target_time, const ros::Duration timeout, std::string* errstr = NULL) const;
00103
00114 virtual bool
00115 canTransform(const std::string& target_frame, const ros::Time& target_time,
00116 const std::string& source_frame, const ros::Time& source_time,
00117 const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr = NULL) const;
00118
00119
00120
00121
00122 private:
00123 bool getFrames(tf2_msgs::FrameGraph::Request& req, tf2_msgs::FrameGraph::Response& res) ;
00124
00125
00126
00127 bool checkAndErrorDedicatedThreadPresent(std::string* errstr) const;
00128
00129 ros::ServiceServer frames_server_;
00130
00131
00132 };
00133
00134 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 seperate thread servicing tf messages, call setUsingDedicatedThread(true) on your Buffer instance.";
00135
00136
00137 }
00138
00139 #endif // TF2_ROS_BUFFER_H