38 #include <tf/tfMessage.h> 55 TFPair(
const std::string& source_frame,
56 const std::string& target_frame,
57 float angular_thres = 0.0f,
58 float trans_thres = 0.0f) :
tf::Transform tf_transmitted_
std::string source_frame_
void setTargetFrame(const std::string &target_frame)
void setSourceFrame(const std::string &source_frame)
const std::string & getSourceFrame() const
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
void updateTransform(geometry_msgs::TransformStamped &update)
tfScalar angle(const Quaternion &q) const
const std::string getID()
const std::string & getTargetFrame() const
void setTransThres(float trans_thres)
std::string target_frame_
void setAngularThres(float angular_thres)
static void transformMsgToTF(const geometry_msgs::Transform &msg, Transform &bt)
void transmissionTriggered()
boost::shared_ptr< TFPair > TFPairPtr
tf::Transform tf_received_
TFPair(const std::string &source_frame, const std::string &target_frame, float angular_thres=0.0f, float trans_thres=0.0f)