Fawkes API  Fawkes Development Version
fawkes::tf::Transformer Class Reference

Coordinate transforms between any two frames in a system. More...

#include <>>

Inheritance diagram for fawkes::tf::Transformer:

Public Member Functions

 Transformer (float cache_time_sec=10.0)
 Constructor. More...
 
virtual ~Transformer (void)
 Destructor. More...
 
void clear ()
 Clear cached transforms. More...
 
bool set_transform (const StampedTransform &transform, const std::string &authority="default_authority")
 Set a transform. More...
 
bool frame_exists (const std::string &frame_id_str) const
 Check if frame exists. More...
 
void lookup_transform (const std::string &target_frame, const std::string &source_frame, const fawkes::Time &time, StampedTransform &transform) const
 Lookup transform. More...
 
void lookup_transform (const std::string &target_frame, const std::string &source_frame, StampedTransform &transform) const
 Lookup transform at latest common time. More...
 
void lookup_transform (const std::string &target_frame, const fawkes::Time &target_time, const std::string &source_frame, const fawkes::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
 Lookup transform assuming a fixed frame. More...
 
bool can_transform (const std::string &target_frame, const std::string &source_frame, const fawkes::Time &time) const
 Test if a transform is possible. More...
 
bool can_transform (const std::string &target_frame, const fawkes::Time &target_time, const std::string &source_frame, const fawkes::Time &source_time, const std::string &fixed_frame) const
 Test if a transform is possible. More...
 
const TimeCacheget_frame_cache (const std::string &frame_id) const
 An accessor to get access to the frame cache. More...
 
void set_enabled (bool enabled)
 Set transformer enabled or disabled. More...
 
bool is_enabled () const
 Check if transformer is enabled. More...
 
int get_latest_common_time (const std::string &source_frame, const std::string &target_frame, fawkes::Time &time, std::string *error_string=0) const
 Get latest common time of two frames. More...
 
void transform_quaternion (const std::string &target_frame, const Stamped< Quaternion > &stamped_in, Stamped< Quaternion > &stamped_out) const
 Transform a stamped Quaternion into the target frame. More...
 
void transform_vector (const std::string &target_frame, const Stamped< Vector3 > &stamped_in, Stamped< Vector3 > &stamped_out) const
 Transform a stamped vector into the target frame. More...
 
void transform_point (const std::string &target_frame, const Stamped< Point > &stamped_in, Stamped< Point > &stamped_out) const
 Transform a stamped point into the target frame. More...
 
void transform_pose (const std::string &target_frame, const Stamped< Pose > &stamped_in, Stamped< Pose > &stamped_out) const
 Transform a stamped pose into the target frame. More...
 
void transform_quaternion (const std::string &target_frame, const fawkes::Time &target_time, const Stamped< Quaternion > &stamped_in, const std::string &fixed_frame, Stamped< Quaternion > &stamped_out) const
 Transform a stamped Quaternion into the target frame assuming a fixed frame. More...
 
void transform_vector (const std::string &target_frame, const fawkes::Time &target_time, const Stamped< Vector3 > &stamped_in, const std::string &fixed_frame, Stamped< Vector3 > &stamped_out) const
 Transform a stamped vector into the target frame assuming a fixed frame. More...
 
void transform_point (const std::string &target_frame, const fawkes::Time &target_time, const Stamped< Point > &stamped_in, const std::string &fixed_frame, Stamped< Point > &stamped_out) const
 Transform a stamped point into the target frame assuming a fixed frame. More...
 
void transform_pose (const std::string &target_frame, const fawkes::Time &target_time, const Stamped< Pose > &stamped_in, const std::string &fixed_frame, Stamped< Pose > &stamped_out) const
 Transform a stamped pose into the target frame assuming a fixed frame. More...
 

Static Public Attributes

static const unsigned int MAX_GRAPH_DEPTH = 100UL
 Maximum number of times to recurse before assuming the tree has a loop. More...
 
static const float DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0.f
 The default amount of time to extrapolate. More...
 

Protected Types

typedef std::unordered_map< std::string, CompactFrameID > M_StringToCompactFrameID
 Map from string frame ids to CompactFrameID. More...
 

Protected Member Functions

TimeCacheget_frame (unsigned int frame_number) const
 An accessor to get a frame. More...
 
CompactFrameID lookup_frame_number (const std::string &frameid_str) const
 String to number for frame lookup. More...
 
CompactFrameID lookup_or_insert_frame_number (const std::string &frameid_str)
 String to number for frame lookup with dynamic allocation of new frames. More...
 
std::string lookup_frame_string (unsigned int frame_id_num) const
 Get frame ID given its number. More...
 

Protected Attributes

bool enabled_
 Flag to mark the transformer as disabled. More...
 
M_StringToCompactFrameID frameIDs_
 Map from frame IDs to frame numbers. More...
 
std::vector< std::string > frameIDs_reverse
 Map from CompactFrameID frame_id_numbers to string for debugging and output. More...
 
std::map< CompactFrameID, std::string > frame_authority_
 Map to lookup the most recent authority for a given frame. More...
 
std::vector< TimeCache * > frames_
 The pointers to potential frames that the tree can be made of. More...
 
Mutexframe_mutex_
 A mutex to protect testing and allocating new frames on the above vector. More...
 
float cache_time_
 How long to cache transform history. More...
 
float max_extrapolation_distance_
 whether or not to allow extrapolation More...
 
std::string tf_prefix_
 transform prefix to apply as necessary More...
 
bool fall_back_to_wall_time_
 Set to true to allow falling back to wall time. More...
 

Detailed Description

Coordinate transforms between any two frames in a system.

This class provides a simple interface to allow recording and lookup of relationships between arbitrary frames of the system.

TF assumes that there is a tree of coordinate frame transforms which define the relationship between all coordinate frames. For example your typical robot would have a transform from global to real world. And then from base to hand, and from base to head. But Base to Hand really is composed of base to shoulder to elbow to wrist to hand. TF is designed to take care of all the intermediate steps for you.

Internal Representation TF will store frames with the parameters necessary for generating the transform into that frame from it's parent and a reference to the parent frame. Frames are designated using an std::string 0 is a frame without a parent (the top of a tree) The positions of frames over time must be pushed in.

All function calls which pass frame ids can potentially throw the exception fawkes::tf::LookupException

Definition at line 79 of file transformer.h.

Member Typedef Documentation

typedef std::unordered_map<std::string, CompactFrameID> fawkes::tf::Transformer::M_StringToCompactFrameID
protected

Map from string frame ids to CompactFrameID.

Definition at line 172 of file transformer.h.

Constructor & Destructor Documentation

fawkes::tf::Transformer::Transformer ( float  cache_time = 10.0)

Constructor.

Parameters
cache_timetime in seconds to cache incoming transforms

Definition at line 267 of file transformer.cpp.

References DEFAULT_MAX_EXTRAPOLATION_DISTANCE, frame_mutex_, frameIDs_, frameIDs_reverse, frames_, and max_extrapolation_distance_.

fawkes::tf::Transformer::~Transformer ( void  )
virtual

Destructor.

Definition at line 282 of file transformer.cpp.

References frame_mutex_, and frames_.

Member Function Documentation

bool fawkes::tf::Transformer::can_transform ( const std::string &  target_frame,
const std::string &  source_frame,
const fawkes::Time time 
) const

Test if a transform is possible.

Parameters
target_frameThe frame into which to transform
source_frameThe frame from which to transform
timeThe time at which to transform
Returns
true if the transformation can be calculated, false otherwise

Definition at line 982 of file transformer.cpp.

References frame_exists(), frame_mutex_, and lookup_frame_number().

Referenced by can_transform().

bool fawkes::tf::Transformer::can_transform ( const std::string &  target_frame,
const fawkes::Time target_time,
const std::string &  source_frame,
const fawkes::Time source_time,
const std::string &  fixed_frame 
) const

Test if a transform is possible.

Parameters
target_frameThe frame into which to transform
target_timeThe time into which to transform
source_frameThe frame from which to transform
source_timeThe time from which to transform
fixed_frameThe frame in which to treat the transform as constant in time
Returns
true if the transformation can be calculated, false otherwise

Definition at line 1011 of file transformer.cpp.

References can_transform().

void fawkes::tf::Transformer::clear ( void  )

Clear cached transforms.

Definition at line 306 of file transformer.cpp.

References frame_mutex_, and frames_.

bool fawkes::tf::Transformer::frame_exists ( const std::string &  frame_id_str) const

Check if frame exists.

Parameters
frame_id_strframe ID
Returns
true if frame exists, false otherwise

Definition at line 325 of file transformer.cpp.

References frame_mutex_, and frameIDs_.

Referenced by can_transform(), get_latest_common_time(), TfExampleThread::loop(), and KatanaActThread::loop().

TimeCache * fawkes::tf::Transformer::get_frame ( unsigned int  frame_number) const
protected

An accessor to get a frame.

This is an internal function which will get the pointer to the frame associated with the frame id

Parameters
frame_numberThe frameID of the desired reference frame
Returns
time cache for given frame number
Exceptions
LookupExceptionthrown if lookup fails
Todo:
check larger values too

Definition at line 769 of file transformer.cpp.

References frames_.

Referenced by set_transform().

const TimeCache * fawkes::tf::Transformer::get_frame_cache ( const std::string &  frame_id) const

An accessor to get access to the frame cache.

Parameters
frame_idframe ID
Returns
time cache for given frame ID
Exceptions
LookupExceptionthrown if lookup fails

Definition at line 784 of file transformer.cpp.

References frames_, and lookup_frame_number().

Referenced by TfExampleThread::loop().

int fawkes::tf::Transformer::get_latest_common_time ( const std::string &  source_frame,
const std::string &  target_frame,
fawkes::Time time,
std::string *  error_string = 0 
) const

Get latest common time of two frames.

Parameters
source_framesource frame ID
target_frameframe target frame ID
timeupon return contains latest common timestamp
error_stringupon error contains accumulated error message.
Returns
value from ErrorValues

Definition at line 674 of file transformer.cpp.

References frame_exists(), and lookup_frame_number().

bool fawkes::tf::Transformer::is_enabled ( ) const
inline

Check if transformer is enabled.

Returns
true if enabled, false otherwise

Definition at line 125 of file transformer.h.

CompactFrameID fawkes::tf::Transformer::lookup_frame_number ( const std::string &  frameid_str) const
protected

String to number for frame lookup.

Parameters
frameid_strframe ID
Returns
frame number
Exceptions
LookupExceptionif frame ID is unknown

Definition at line 801 of file transformer.cpp.

References frameIDs_.

Referenced by can_transform(), get_frame_cache(), get_latest_common_time(), and lookup_transform().

std::string fawkes::tf::Transformer::lookup_frame_string ( unsigned int  frame_num) const
protected

Get frame ID given its number.

Parameters
frame_numframe number
Returns
frame ID string
Exceptions
LookupExceptionthrown if number invalid

Definition at line 847 of file transformer.cpp.

References frameIDs_reverse.

CompactFrameID fawkes::tf::Transformer::lookup_or_insert_frame_number ( const std::string &  frameid_str)
protected

String to number for frame lookup with dynamic allocation of new frames.

Parameters
frameid_strframe ID
Returns
frame number, if none existed for the given frame ID a new one is created

Definition at line 824 of file transformer.cpp.

References cache_time_, frameIDs_, frameIDs_reverse, and frames_.

Referenced by set_transform().

void fawkes::tf::Transformer::lookup_transform ( const std::string &  target_frame,
const std::string &  source_frame,
const fawkes::Time time,
StampedTransform transform 
) const

Lookup transform.

Parameters
target_frametarget frame ID
source_framesource frame ID
timetime for which to get the transform, set to (0,0) to get latest common time frame
transformupon return contains the transform
Exceptions
ConnectivityExceptionthrown if no connection between the source and target frame could be found in the tree.
ExtrapolationExceptionreturning a value would have required extrapolation beyond current limits.
LookupExceptionat least one of the two given frames is unknown

Definition at line 869 of file transformer.cpp.

References fawkes::tf::StampedTransform::child_frame_id, enabled_, fawkes::tf::StampedTransform::frame_id, frame_mutex_, lookup_frame_number(), fawkes::tf::TransformAccum::result_quat, fawkes::tf::TransformAccum::result_vec, fawkes::tf::StampedTransform::stamp, and fawkes::tf::TransformAccum::time.

Referenced by LaserProjectionDataFilter::filter(), lookup_transform(), TfExampleThread::loop(), TabletopObjectsThread::loop(), transform_point(), transform_pose(), transform_quaternion(), and transform_vector().

void fawkes::tf::Transformer::lookup_transform ( const std::string &  target_frame,
const std::string &  source_frame,
StampedTransform transform 
) const

Lookup transform at latest common time.

Parameters
target_frametarget frame ID
source_framesource frame ID
transformupon return contains the transform
Exceptions
ConnectivityExceptionthrown if no connection between the source and target frame could be found in the tree.
ExtrapolationExceptionreturning a value would have required extrapolation beyond current limits.
LookupExceptionat least one of the two given frames is unknown

Definition at line 932 of file transformer.cpp.

References lookup_transform().

void fawkes::tf::Transformer::lookup_transform ( const std::string &  target_frame,
const fawkes::Time target_time,
const std::string &  source_frame,
const fawkes::Time source_time,
const std::string &  fixed_frame,
StampedTransform transform 
) const

Lookup transform assuming a fixed frame.

This will lookup a transformation from source to target, assuming that there is a fixed frame, by first finding the transform of the source frame in the fixed frame, and then a transformation from the fixed frame to the target frame.

Parameters
target_frametarget frame ID
target_timetime for the target frame
source_framesource frame ID
source_timetime in the source frame
fixed_frameID of fixed frame
transformupon return contains the transform
Exceptions
ConnectivityExceptionthrown if no connection between the source and target frame could be found in the tree.
ExtrapolationExceptionreturning a value would have required extrapolation beyond current limits.
LookupExceptionat least one of the two given frames is unknown

Definition at line 959 of file transformer.cpp.

References fawkes::tf::StampedTransform::child_frame_id, fawkes::tf::StampedTransform::frame_id, lookup_transform(), fawkes::tf::StampedTransform::set_data(), and fawkes::tf::StampedTransform::stamp.

void fawkes::tf::Transformer::set_enabled ( bool  enabled)

Set transformer enabled or disabled.

Parameters
enabledtrue to enable, false to disable

Definition at line 299 of file transformer.cpp.

References enabled_.

Referenced by fawkes::tf::TransformListener::TransformListener().

bool fawkes::tf::Transformer::set_transform ( const StampedTransform transform,
const std::string &  authority = "default_authority" 
)

Set a transform.

Parameters
transformtransform to set
authorityauthority from which the transform was received.
Returns
true on success, false otherwise

Definition at line 698 of file transformer.cpp.

References cache_time_, fawkes::tf::StampedTransform::child_frame_id, frame_authority_, fawkes::tf::StampedTransform::frame_id, frame_mutex_, frames_, get_frame(), fawkes::tf::TimeCache::insert_data(), lookup_or_insert_frame_number(), and fawkes::tf::StampedTransform::stamp.

void fawkes::tf::Transformer::transform_point ( const std::string &  target_frame,
const Stamped< Point > &  stamped_in,
Stamped< Point > &  stamped_out 
) const

Transform a stamped point into the target frame.

This transforms the point given relative to the frame set in the stamped point into the target frame.

Parameters
target_frameframe into which to transform
stamped_instamped point, defines source frame and time
stamped_outstamped output point in target_frame
Exceptions
ConnectivityExceptionthrown if no connection between the source and target frame could be found in the tree.
ExtrapolationExceptionreturning a value would have required extrapolation beyond current limits.
LookupExceptionat least one of the two given frames is unknown

Definition at line 1122 of file transformer.cpp.

References fawkes::tf::Stamped< T >::frame_id, lookup_transform(), fawkes::tf::Stamped< T >::set_data(), fawkes::tf::StampedTransform::stamp, and fawkes::tf::Stamped< T >::stamp.

Referenced by TabletopVisualizationThread::loop(), TabletopObjectsThread::loop(), and KatanaActThread::loop().

void fawkes::tf::Transformer::transform_point ( const std::string &  target_frame,
const fawkes::Time target_time,
const Stamped< Point > &  stamped_in,
const std::string &  fixed_frame,
Stamped< Point > &  stamped_out 
) const

Transform a stamped point into the target frame assuming a fixed frame.

This transforms the point relative to the frame set in the stamped quaternion into the target frame. This will transform the point from source to target, assuming that there is a fixed frame, by first finding the transform of the source frame in the fixed frame, and then a transformation from the fixed frame into the target frame.

Parameters
target_frameframe into which to transform
target_timedesired time in the target frame
stamped_instamped point, defines source frame and time
fixed_frameID of fixed frame
stamped_outstamped output point in target_frame
Exceptions
ConnectivityExceptionthrown if no connection between the source and target frame could be found in the tree.
ExtrapolationExceptionreturning a value would have required extrapolation beyond current limits.
LookupExceptionat least one of the two given frames is unknown

Definition at line 1265 of file transformer.cpp.

References fawkes::tf::Stamped< T >::frame_id, lookup_transform(), fawkes::tf::Stamped< T >::set_data(), fawkes::tf::StampedTransform::stamp, and fawkes::tf::Stamped< T >::stamp.

void fawkes::tf::Transformer::transform_pose ( const std::string &  target_frame,
const Stamped< Pose > &  stamped_in,
Stamped< Pose > &  stamped_out 
) const

Transform a stamped pose into the target frame.

This transforms the pose given relative to the frame set in the stamped vector into the target frame.

Parameters
target_frameframe into which to transform
stamped_instamped pose, defines source frame and time
stamped_outstamped output pose in target_frame
Exceptions
ConnectivityExceptionthrown if no connection between the source and target frame could be found in the tree.
ExtrapolationExceptionreturning a value would have required extrapolation beyond current limits.
LookupExceptionat least one of the two given frames is unknown

Definition at line 1150 of file transformer.cpp.

References fawkes::tf::Stamped< T >::frame_id, lookup_transform(), fawkes::tf::Stamped< T >::set_data(), fawkes::tf::StampedTransform::stamp, and fawkes::tf::Stamped< T >::stamp.

Referenced by AmclThread::loop().

void fawkes::tf::Transformer::transform_pose ( const std::string &  target_frame,
const fawkes::Time target_time,
const Stamped< Pose > &  stamped_in,
const std::string &  fixed_frame,
Stamped< Pose > &  stamped_out 
) const

Transform a stamped pose into the target frame assuming a fixed frame.

This transforms the pose relative to the frame set in the stamped quaternion into the target frame. This will transform the pose from source to target, assuming that there is a fixed frame, by first finding the transform of the source frame in the fixed frame, and then a transformation from the fixed frame into the target frame.

Parameters
target_frameframe into which to transform
target_timedesired time in the target frame
stamped_instamped pose, defines source frame and time
fixed_frameID of fixed frame
stamped_outstamped output pose in target_frame
Exceptions
ConnectivityExceptionthrown if no connection between the source and target frame could be found in the tree.
ExtrapolationExceptionreturning a value would have required extrapolation beyond current limits.
LookupExceptionat least one of the two given frames is unknown

Definition at line 1301 of file transformer.cpp.

References fawkes::tf::Stamped< T >::frame_id, lookup_transform(), fawkes::tf::Stamped< T >::set_data(), fawkes::tf::StampedTransform::stamp, and fawkes::tf::Stamped< T >::stamp.

void fawkes::tf::Transformer::transform_quaternion ( const std::string &  target_frame,
const Stamped< Quaternion > &  stamped_in,
Stamped< Quaternion > &  stamped_out 
) const

Transform a stamped Quaternion into the target frame.

This transforms the quaternion relative to the frame set in the stamped quaternion into the target frame.

Parameters
target_frameframe into which to transform
stamped_instamped quaternion, defines source frame and time
stamped_outstamped output quaternion in target_frame
Exceptions
ConnectivityExceptionthrown if no connection between the source and target frame could be found in the tree.
ExtrapolationExceptionreturning a value would have required extrapolation beyond current limits.
LookupExceptionat least one of the two given frames is unknown
InvalidArgumentthrown if the Quaternion is invalid, most likely an uninitialized Quaternion (0,0,0,0).

Definition at line 1061 of file transformer.cpp.

References fawkes::tf::Stamped< T >::frame_id, lookup_transform(), fawkes::tf::Stamped< T >::set_data(), fawkes::tf::StampedTransform::stamp, and fawkes::tf::Stamped< T >::stamp.

Referenced by AmclThread::loop().

void fawkes::tf::Transformer::transform_quaternion ( const std::string &  target_frame,
const fawkes::Time target_time,
const Stamped< Quaternion > &  stamped_in,
const std::string &  fixed_frame,
Stamped< Quaternion > &  stamped_out 
) const

Transform a stamped Quaternion into the target frame assuming a fixed frame.

This transforms the quaternion relative to the frame set in the stamped quaternion into the target frame. This will transform the quaternion from source to target, assuming that there is a fixed frame, by first finding the transform of the source frame in the fixed frame, and then a transformation from the fixed frame into the target frame.

Parameters
target_frameframe into which to transform
target_timedesired time in the target frame
stamped_instamped quaternion, defines source frame and time
fixed_frameID of fixed frame
stamped_outstamped output quaternion in target_frame
Exceptions
ConnectivityExceptionthrown if no connection between the source and target frame could be found in the tree.
ExtrapolationExceptionreturning a value would have required extrapolation beyond current limits.
LookupExceptionat least one of the two given frames is unknown
InvalidArgumentthrown if the Quaternion is invalid, most likely an uninitialized Quaternion (0,0,0,0).

Definition at line 1186 of file transformer.cpp.

References fawkes::tf::Stamped< T >::frame_id, lookup_transform(), fawkes::tf::Stamped< T >::set_data(), fawkes::tf::StampedTransform::stamp, and fawkes::tf::Stamped< T >::stamp.

void fawkes::tf::Transformer::transform_vector ( const std::string &  target_frame,
const Stamped< Vector3 > &  stamped_in,
Stamped< Vector3 > &  stamped_out 
) const

Transform a stamped vector into the target frame.

This transforms the vector given relative to the frame set in the stamped vector into the target frame.

Parameters
target_frameframe into which to transform
stamped_instamped vector, defines source frame and time
stamped_outstamped output vector in target_frame
Exceptions
ConnectivityExceptionthrown if no connection between the source and target frame could be found in the tree.
ExtrapolationExceptionreturning a value would have required extrapolation beyond current limits.
LookupExceptionat least one of the two given frames is unknown

Definition at line 1090 of file transformer.cpp.

References fawkes::tf::Stamped< T >::frame_id, lookup_transform(), fawkes::tf::Stamped< T >::set_data(), fawkes::tf::StampedTransform::stamp, and fawkes::tf::Stamped< T >::stamp.

Referenced by TabletopObjectsThread::loop().

void fawkes::tf::Transformer::transform_vector ( const std::string &  target_frame,
const fawkes::Time target_time,
const Stamped< Vector3 > &  stamped_in,
const std::string &  fixed_frame,
Stamped< Vector3 > &  stamped_out 
) const

Transform a stamped vector into the target frame assuming a fixed frame.

This transforms the vector relative to the frame set in the stamped quaternion into the target frame. This will transform the vector from source to target, assuming that there is a fixed frame, by first finding the transform of the source frame in the fixed frame, and then a transformation from the fixed frame into the target frame.

Parameters
target_frameframe into which to transform
target_timedesired time in the target frame
stamped_instamped vector, defines source frame and time
fixed_frameID of fixed frame
stamped_outstamped output vector in target_frame
Exceptions
ConnectivityExceptionthrown if no connection between the source and target frame could be found in the tree.
ExtrapolationExceptionreturning a value would have required extrapolation beyond current limits.
LookupExceptionat least one of the two given frames is unknown

Definition at line 1223 of file transformer.cpp.

References fawkes::tf::Stamped< T >::frame_id, lookup_transform(), fawkes::tf::Stamped< T >::set_data(), fawkes::tf::StampedTransform::stamp, and fawkes::tf::Stamped< T >::stamp.

Member Data Documentation

float fawkes::tf::Transformer::cache_time_
protected

How long to cache transform history.

Definition at line 189 of file transformer.h.

Referenced by lookup_or_insert_frame_number(), and set_transform().

const float fawkes::tf::Transformer::DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0.f
static

The default amount of time to extrapolate.

Definition at line 83 of file transformer.h.

Referenced by Transformer().

bool fawkes::tf::Transformer::enabled_
protected

Flag to mark the transformer as disabled.

Definition at line 167 of file transformer.h.

Referenced by lookup_transform(), and set_enabled().

bool fawkes::tf::Transformer::fall_back_to_wall_time_
protected

Set to true to allow falling back to wall time.

Definition at line 198 of file transformer.h.

std::map<CompactFrameID, std::string> fawkes::tf::Transformer::frame_authority_
protected

Map to lookup the most recent authority for a given frame.

Definition at line 179 of file transformer.h.

Referenced by set_transform().

Mutex* fawkes::tf::Transformer::frame_mutex_
mutableprotected

A mutex to protect testing and allocating new frames on the above vector.

Definition at line 186 of file transformer.h.

Referenced by can_transform(), clear(), frame_exists(), lookup_transform(), set_transform(), Transformer(), and ~Transformer().

M_StringToCompactFrameID fawkes::tf::Transformer::frameIDs_
protected

Map from frame IDs to frame numbers.

Definition at line 175 of file transformer.h.

Referenced by frame_exists(), lookup_frame_number(), lookup_or_insert_frame_number(), and Transformer().

std::vector<std::string> fawkes::tf::Transformer::frameIDs_reverse
protected

Map from CompactFrameID frame_id_numbers to string for debugging and output.

Definition at line 177 of file transformer.h.

Referenced by lookup_frame_string(), lookup_or_insert_frame_number(), and Transformer().

std::vector<TimeCache*> fawkes::tf::Transformer::frames_
protected

The pointers to potential frames that the tree can be made of.

The frames will be dynamically allocated at run time when set the first time.

Definition at line 183 of file transformer.h.

Referenced by clear(), get_frame(), get_frame_cache(), lookup_or_insert_frame_number(), set_transform(), Transformer(), and ~Transformer().

float fawkes::tf::Transformer::max_extrapolation_distance_
protected

whether or not to allow extrapolation

Definition at line 192 of file transformer.h.

Referenced by Transformer().

static const unsigned int fawkes::tf::Transformer::MAX_GRAPH_DEPTH = 100UL
static

Maximum number of times to recurse before assuming the tree has a loop.

Parameters
staticconst int64_t Transformer::DEFAULT_MAX_EXTRAPOLATION_DISTANCE The default amount of time to extrapolate.

Definition at line 82 of file transformer.h.

std::string fawkes::tf::Transformer::tf_prefix_
protected

transform prefix to apply as necessary

Definition at line 195 of file transformer.h.


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