Public Member Functions | Public Attributes | Private Attributes
TFPair Class Reference

#include <tf_pair.h>

List of all members.

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::TFPair ( ) [inline]

Definition at line 46 of file tf_pair.h.

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 ( ) [inline]

Definition at line 69 of file tf_pair.h.


Member Function Documentation

float TFPair::getAngularThres ( ) [inline]

Definition at line 101 of file tf_pair.h.

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

Definition at line 149 of file tf_pair.h.

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

Definition at line 79 of file tf_pair.h.

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

Definition at line 90 of file tf_pair.h.

float TFPair::getTransThres ( ) [inline]

Definition at line 112 of file tf_pair.h.

void TFPair::setAngularThres ( float  angular_thres) [inline]

Definition at line 95 of file tf_pair.h.

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

Definition at line 73 of file tf_pair.h.

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

Definition at line 84 of file tf_pair.h.

void TFPair::setTransThres ( float  trans_thres) [inline]

Definition at line 106 of file tf_pair.h.

void TFPair::transmissionTriggered ( ) [inline]

Definition at line 123 of file tf_pair.h.

bool TFPair::updateNeeded ( ) [inline]

Definition at line 128 of file tf_pair.h.

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

Definition at line 117 of file tf_pair.h.


Member Data Documentation

float TFPair::angular_thres_ [private]

Definition at line 161 of file tf_pair.h.

Definition at line 168 of file tf_pair.h.

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.

std::string TFPair::source_frame_ [private]

Definition at line 158 of file tf_pair.h.

std::string TFPair::target_frame_ [private]

Definition at line 159 of file tf_pair.h.

Definition at line 165 of file tf_pair.h.

Definition at line 164 of file tf_pair.h.

float TFPair::trans_thres_ [private]

Definition at line 162 of file tf_pair.h.

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 Thu Jun 6 2019 20:34:26