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
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef TF2_ROS_BUFFER_CLIENT_H_
00038 #define TF2_ROS_BUFFER_CLIENT_H_
00039
00040 #include <tf2_ros/buffer_interface.h>
00041 #include <actionlib/client/simple_action_client.h>
00042 #include <tf2_msgs/LookupTransformAction.h>
00043
00044 namespace tf2_ros
00045 {
00046 class BufferClient : public BufferInterface
00047 {
00048 public:
00049 typedef actionlib::SimpleActionClient<tf2_msgs::LookupTransformAction> LookupActionClient;
00050
00056 BufferClient(std::string ns, double check_frequency = 10.0, ros::Duration timeout_padding_ = ros::Duration(2.0));
00057
00068 virtual geometry_msgs::TransformStamped
00069 lookupTransform(const std::string& target_frame, const std::string& source_frame,
00070 const ros::Time& time, const ros::Duration timeout = ros::Duration(0.0)) const;
00071
00084 virtual geometry_msgs::TransformStamped
00085 lookupTransform(const std::string& target_frame, const ros::Time& target_time,
00086 const std::string& source_frame, const ros::Time& source_time,
00087 const std::string& fixed_frame, const ros::Duration timeout = ros::Duration(0.0)) const;
00088
00097 virtual bool
00098 canTransform(const std::string& target_frame, const std::string& source_frame,
00099 const ros::Time& time, const ros::Duration timeout = ros::Duration(0.0), std::string* errstr = NULL) const;
00100
00111 virtual bool
00112 canTransform(const std::string& target_frame, const ros::Time& target_time,
00113 const std::string& source_frame, const ros::Time& source_time,
00114 const std::string& fixed_frame, const ros::Duration timeout = ros::Duration(0.0), std::string* errstr = NULL) const;
00115
00116 bool waitForServer(const ros::Duration& timeout = ros::Duration(0))
00117 {
00118 return client_.waitForServer(timeout);
00119 }
00120
00121 private:
00122 geometry_msgs::TransformStamped processGoal(const tf2_msgs::LookupTransformGoal& goal) const;
00123 geometry_msgs::TransformStamped processResult(const tf2_msgs::LookupTransformResult& result) const;
00124 mutable LookupActionClient client_;
00125 double check_frequency_;
00126 ros::Duration timeout_padding_;
00127 };
00128 };
00129 #endif