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
00040
00041 namespace tf2
00042 {
00043
00044
00045 class Buffer: public BufferInterface, public BufferCore
00046 {
00047 public:
00048 using BufferCore::lookupTransform;
00049 using BufferCore::canTransform;
00050
00057 Buffer(ros::Duration cache_time = ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug = true);
00058
00069 virtual geometry_msgs::TransformStamped
00070 lookupTransform(const std::string& target_frame, const std::string& source_frame,
00071 const ros::Time& time, const ros::Duration timeout) const;
00072
00085 virtual geometry_msgs::TransformStamped
00086 lookupTransform(const std::string& target_frame, const ros::Time& target_time,
00087 const std::string& source_frame, const ros::Time& source_time,
00088 const std::string& fixed_frame, const ros::Duration timeout) const;
00089
00090
00099 virtual bool
00100 canTransform(const std::string& target_frame, const std::string& source_frame,
00101 const ros::Time& target_time, const ros::Duration timeout, std::string* errstr = NULL) const;
00102
00113 virtual bool
00114 canTransform(const std::string& target_frame, const ros::Time& target_time,
00115 const std::string& source_frame, const ros::Time& source_time,
00116 const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr = NULL) const;
00117
00118 private:
00119 bool getFrames(tf2_msgs::FrameGraph::Request& req, tf2_msgs::FrameGraph::Response& res)
00120 {
00121 res.frame_yaml = allFramesAsYAML();
00122 return true;
00123 }
00124
00125 ros::ServiceServer frames_server_;
00126
00127 };
00128
00129 }
00130
00131 #endif // TF2_ROS_BUFFER_H