#include <tf_pair.h>
Definition at line 42 of file tf_pair.h.
◆ TFPair() [1/2]
◆ 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 |
◆ ~TFPair()
◆ getAngularThres()
float TFPair::getAngularThres |
( |
| ) |
|
|
inline |
◆ getID()
const std::string TFPair::getID |
( |
| ) |
|
|
inline |
◆ getSourceFrame()
const std::string& TFPair::getSourceFrame |
( |
| ) |
const |
|
inline |
◆ getTargetFrame()
const std::string& TFPair::getTargetFrame |
( |
| ) |
const |
|
inline |
◆ getTransThres()
float TFPair::getTransThres |
( |
| ) |
|
|
inline |
◆ setAngularThres()
void TFPair::setAngularThres |
( |
float |
angular_thres | ) |
|
|
inline |
◆ setSourceFrame()
void TFPair::setSourceFrame |
( |
const std::string & |
source_frame | ) |
|
|
inline |
◆ setTargetFrame()
void TFPair::setTargetFrame |
( |
const std::string & |
target_frame | ) |
|
|
inline |
◆ setTransThres()
void TFPair::setTransThres |
( |
float |
trans_thres | ) |
|
|
inline |
◆ transmissionTriggered()
void TFPair::transmissionTriggered |
( |
| ) |
|
|
inline |
◆ updateNeeded()
bool TFPair::updateNeeded |
( |
| ) |
|
|
inline |
◆ updateTransform()
void TFPair::updateTransform |
( |
geometry_msgs::TransformStamped & |
update | ) |
|
|
inline |
◆ angular_thres_
float TFPair::angular_thres_ |
|
private |
◆ first_transmission_
bool TFPair::first_transmission_ |
|
private |
◆ 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 189 of file tf_pair.h.
◆ source_frame_
std::string TFPair::source_frame_ |
|
private |
◆ target_frame_
std::string TFPair::target_frame_ |
|
private |
◆ tf_received_
◆ tf_transmitted_
◆ trans_thres_
float TFPair::trans_thres_ |
|
private |
◆ updated_
The documentation for this class was generated from the following file: