Public Member Functions | Public Attributes | Private Attributes | List of all members
TFPair Class Reference

#include <tf_pair.h>

Public Member Functions

float getAngularThres ()
 
const std::string getID ()
 
const std::string & getSourceFrame () const
 
const std::string & getTargetFrame () const
 
float getTransThres ()
 
void setAngularThres (float angular_thres)
 
void setSourceFrame (const std::string &source_frame)
 
void setTargetFrame (const std::string &target_frame)
 
void setTransThres (float trans_thres)
 
 TFPair ()
 
 TFPair (const std::string &source_frame, const std::string &target_frame, float angular_thres=0.0f, float trans_thres=0.0f)
 
void transmissionTriggered ()
 
bool updateNeeded ()
 
void updateTransform (geometry_msgs::TransformStamped &update)
 
 ~TFPair ()
 

Public Attributes

bool is_okay
 

Private Attributes

float angular_thres_
 
bool first_transmission_
 
std::string source_frame_
 
std::string target_frame_
 
tf::Transform tf_received_
 
tf::Transform tf_transmitted_
 
float trans_thres_
 
bool updated_
 

Detailed Description

Definition at line 42 of file tf_pair.h.

Constructor & Destructor Documentation

◆ TFPair() [1/2]

TFPair::TFPair ( )
inline

Definition at line 46 of file tf_pair.h.

◆ TFPair() [2/2]

TFPair::TFPair ( const std::string &  source_frame,
const std::string &  target_frame,
float  angular_thres = 0.0f,
float  trans_thres = 0.0f 
)
inline

Definition at line 55 of file tf_pair.h.

◆ ~TFPair()

TFPair::~TFPair ( )
inline

Definition at line 69 of file tf_pair.h.

Member Function Documentation

◆ getAngularThres()

float TFPair::getAngularThres ( )
inline

Definition at line 101 of file tf_pair.h.

◆ getID()

const std::string TFPair::getID ( )
inline

Definition at line 149 of file tf_pair.h.

◆ getSourceFrame()

const std::string& TFPair::getSourceFrame ( ) const
inline

Definition at line 79 of file tf_pair.h.

◆ getTargetFrame()

const std::string& TFPair::getTargetFrame ( ) const
inline

Definition at line 90 of file tf_pair.h.

◆ getTransThres()

float TFPair::getTransThres ( )
inline

Definition at line 112 of file tf_pair.h.

◆ setAngularThres()

void TFPair::setAngularThres ( float  angular_thres)
inline

Definition at line 95 of file tf_pair.h.

◆ setSourceFrame()

void TFPair::setSourceFrame ( const std::string &  source_frame)
inline

Definition at line 73 of file tf_pair.h.

◆ setTargetFrame()

void TFPair::setTargetFrame ( const std::string &  target_frame)
inline

Definition at line 84 of file tf_pair.h.

◆ setTransThres()

void TFPair::setTransThres ( float  trans_thres)
inline

Definition at line 106 of file tf_pair.h.

◆ transmissionTriggered()

void TFPair::transmissionTriggered ( )
inline

Definition at line 123 of file tf_pair.h.

◆ updateNeeded()

bool TFPair::updateNeeded ( )
inline

Definition at line 128 of file tf_pair.h.

◆ updateTransform()

void TFPair::updateTransform ( geometry_msgs::TransformStamped &  update)
inline

Definition at line 117 of file tf_pair.h.

Member Data Documentation

◆ angular_thres_

float TFPair::angular_thres_
private

Definition at line 161 of file tf_pair.h.

◆ first_transmission_

bool TFPair::first_transmission_
private

Definition at line 168 of file tf_pair.h.

◆ is_okay

bool TFPair::is_okay

save whether this transform is okay, so we can print only a single message if a transform breaks/starts working again

Definition at line 155 of file tf_pair.h.

◆ source_frame_

std::string TFPair::source_frame_
private

Definition at line 158 of file tf_pair.h.

◆ target_frame_

std::string TFPair::target_frame_
private

Definition at line 159 of file tf_pair.h.

◆ tf_received_

tf::Transform TFPair::tf_received_
private

Definition at line 165 of file tf_pair.h.

◆ tf_transmitted_

tf::Transform TFPair::tf_transmitted_
private

Definition at line 164 of file tf_pair.h.

◆ trans_thres_

float TFPair::trans_thres_
private

Definition at line 162 of file tf_pair.h.

◆ updated_

bool TFPair::updated_
private

Definition at line 167 of file tf_pair.h.


The documentation for this class was generated from the following file:


tf2_web_republisher
Author(s): Julius Kammer
autogenerated on Mon Feb 28 2022 23:52:49