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
00051 class Buffer: public BufferInterface, public tf2::BufferCore
00052 {
00053 public:
00054 using tf2::BufferCore::lookupTransform;
00055 using tf2::BufferCore::canTransform;
00056
00063 Buffer(ros::Duration cache_time = ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug = false);
00064
00075 virtual geometry_msgs::TransformStamped
00076 lookupTransform(const std::string& target_frame, const std::string& source_frame,
00077 const ros::Time& time, const ros::Duration timeout) const;
00078
00091 virtual geometry_msgs::TransformStamped
00092 lookupTransform(const std::string& target_frame, const ros::Time& target_time,
00093 const std::string& source_frame, const ros::Time& source_time,
00094 const std::string& fixed_frame, const ros::Duration timeout) const;
00095
00096
00105 virtual bool
00106 canTransform(const std::string& target_frame, const std::string& source_frame,
00107 const ros::Time& target_time, const ros::Duration timeout, std::string* errstr = NULL) const;
00108
00119 virtual bool
00120 canTransform(const std::string& target_frame, const ros::Time& target_time,
00121 const std::string& source_frame, const ros::Time& source_time,
00122 const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr = NULL) const;
00123
00124
00125
00126
00127 private:
00128 bool getFrames(tf2_msgs::FrameGraph::Request& req, tf2_msgs::FrameGraph::Response& res) ;
00129
00130
00131
00132 bool checkAndErrorDedicatedThreadPresent(std::string* errstr) const;
00133
00134 ros::ServiceServer frames_server_;
00135
00136
00137 };
00138
00139 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.";
00140
00141
00142 }
00143
00144 #endif // TF2_ROS_BUFFER_H