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
00038 #include <tf/tfMessage.h>
00039 #include <tf/transform_datatypes.h>
00040
00041
00042 class TFPair
00043 {
00044 public:
00045
00046 TFPair() :
00047 angular_thres_(0.0f), trans_thres_(0.0f), updated_(false), first_transmission_(true)
00048 {
00049 }
00050
00051 TFPair(const std::string& source_frame,
00052 const std::string& target_frame,
00053 float angular_thres = 0.0f,
00054 float trans_thres = 0.0f) :
00055 source_frame_(source_frame),
00056 target_frame_(target_frame),
00057 angular_thres_(angular_thres),
00058 trans_thres_(trans_thres),
00059 updated_(false),
00060 first_transmission_(true)
00061 {
00062 }
00063
00064 ~TFPair()
00065 {
00066 }
00067
00068 void setSourceFrame(const std::string& source_frame)
00069 {
00070 source_frame_ = source_frame;
00071 updated_ = true;
00072 }
00073
00074 const std::string& getSourceFrame() const
00075 {
00076 return source_frame_;
00077 }
00078
00079 void setTargetFrame(const std::string& target_frame)
00080 {
00081 target_frame_ = target_frame;
00082 updated_ = true;
00083 }
00084
00085 const std::string& getTargetFrame() const
00086 {
00087 return target_frame_;
00088 }
00089
00090 void setAngularThres(float angular_thres)
00091 {
00092 angular_thres_ = angular_thres;
00093 updated_ = true;
00094 }
00095
00096 float getAngularThres()
00097 {
00098 return angular_thres_;
00099 }
00100
00101 void setTransThres(float trans_thres)
00102 {
00103 trans_thres_ = trans_thres;
00104 updated_ = true;
00105 }
00106
00107 float getTransThres()
00108 {
00109 return trans_thres_;
00110 }
00111
00112 void updateTransform(geometry_msgs::TransformStamped& update)
00113 {
00114 tf::transformMsgToTF(update.transform, tf_received_);
00115 updated_ = true;
00116 }
00117
00118 void transmissionTriggered()
00119 {
00120 tf_transmitted_ = tf_received_;
00121 }
00122
00123 bool updateNeeded()
00124 {
00125 bool result = false;
00126
00127 if (updated_)
00128 {
00129 if (trans_thres_ == 0.0 || angular_thres_ == 0.0
00130 || tf_transmitted_.getOrigin().distance(tf_received_.getOrigin()) > trans_thres_
00131 || tf_transmitted_.getRotation().angle(tf_received_.getRotation()) > angular_thres_
00132 || first_transmission_)
00133 {
00134 result = true;
00135 first_transmission_ = false;
00136 }
00137 }
00138
00139 updated_ = false;
00140
00141 return result;
00142 }
00143
00144 const std::string getID()
00145 {
00146 return source_frame_+"-"+target_frame_;
00147 }
00148
00149
00150 private:
00151 std::string source_frame_;
00152 std::string target_frame_;
00153
00154 float angular_thres_;
00155 float trans_thres_;
00156
00157 tf::Transform tf_transmitted_;
00158 tf::Transform tf_received_;
00159
00160 bool updated_;
00161 bool first_transmission_;
00162
00163 };
00164
00165 typedef boost::shared_ptr<TFPair> TFPairPtr;