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 {
00052 class BufferClient : public BufferInterface
00053 {
00054 public:
00055 typedef actionlib::SimpleActionClient<tf2_msgs::LookupTransformAction> LookupActionClient;
00056
00062 BufferClient(std::string ns, double check_frequency = 10.0, ros::Duration timeout_padding = ros::Duration(2.0));
00063
00074 virtual geometry_msgs::TransformStamped
00075 lookupTransform(const std::string& target_frame, const std::string& source_frame,
00076 const ros::Time& time, const ros::Duration timeout = ros::Duration(0.0)) const;
00077
00090 virtual geometry_msgs::TransformStamped
00091 lookupTransform(const std::string& target_frame, const ros::Time& target_time,
00092 const std::string& source_frame, const ros::Time& source_time,
00093 const std::string& fixed_frame, const ros::Duration timeout = ros::Duration(0.0)) const;
00094
00103 virtual bool
00104 canTransform(const std::string& target_frame, const std::string& source_frame,
00105 const ros::Time& time, const ros::Duration timeout = ros::Duration(0.0), std::string* errstr = NULL) const;
00106
00117 virtual bool
00118 canTransform(const std::string& target_frame, const ros::Time& target_time,
00119 const std::string& source_frame, const ros::Time& source_time,
00120 const std::string& fixed_frame, const ros::Duration timeout = ros::Duration(0.0), std::string* errstr = NULL) const;
00121
00126 bool waitForServer(const ros::Duration& timeout = ros::Duration(0))
00127 {
00128 return client_.waitForServer(timeout);
00129 }
00130
00131 private:
00132 geometry_msgs::TransformStamped processGoal(const tf2_msgs::LookupTransformGoal& goal) const;
00133 geometry_msgs::TransformStamped processResult(const tf2_msgs::LookupTransformResult& result) const;
00134 mutable LookupActionClient client_;
00135 double check_frequency_;
00136 ros::Duration timeout_padding_;
00137 };
00138 };
00139 #endif