Fawkes API
Fawkes Development Version
|
Coordinate transforms between any two frames in a system. More...
#include <>>
Public Member Functions | |
Transformer (float cache_time_sec=10.0) | |
Constructor. | |
virtual | ~Transformer (void) |
Destructor. | |
void | clear () |
Clear cached transforms. | |
bool | set_transform (const StampedTransform &transform, const std::string &authority="default_authority") |
Set a transform. | |
bool | frame_exists (const std::string &frame_id_str) const |
Check if frame exists. | |
void | lookup_transform (const std::string &target_frame, const std::string &source_frame, const fawkes::Time &time, StampedTransform &transform) const |
Lookup transform. | |
void | lookup_transform (const std::string &target_frame, const std::string &source_frame, StampedTransform &transform) const |
Lookup transform at latest common time. | |
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. | |
bool | can_transform (const std::string &target_frame, const std::string &source_frame, const fawkes::Time &time) const |
Test if a transform is possible. | |
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. | |
const TimeCache * | get_frame_cache (const std::string &frame_id) const |
An accessor to get access to the frame cache. | |
void | set_enabled (bool enabled) |
Set transformer enabled or disabled. | |
bool | is_enabled () const |
Check if transformer is enabled. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
Static Public Attributes | |
static const unsigned int | MAX_GRAPH_DEPTH = 100UL |
Maximum number of times to recurse before assuming the tree has a loop. | |
static const float | DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0.f |
The default amount of time to extrapolate. | |
Protected Types | |
typedef std::unordered_map < std::string, CompactFrameID > | M_StringToCompactFrameID |
Map from string frame ids to CompactFrameID. | |
Protected Member Functions | |
TimeCache * | get_frame (unsigned int frame_number) const |
An accessor to get a frame. | |
CompactFrameID | lookup_frame_number (const std::string &frameid_str) const |
String to number for frame lookup. | |
CompactFrameID | lookup_or_insert_frame_number (const std::string &frameid_str) |
String to number for frame lookup with dynamic allocation of new frames. | |
std::string | lookup_frame_string (unsigned int frame_id_num) const |
Get frame ID given its number. | |
Protected Attributes | |
bool | enabled_ |
Flag to mark the transformer as disabled. | |
M_StringToCompactFrameID | frameIDs_ |
Map from frame IDs to frame numbers. | |
std::vector< std::string > | frameIDs_reverse |
Map from CompactFrameID frame_id_numbers to string for debugging and output. | |
std::map< CompactFrameID, std::string > | frame_authority_ |
Map to lookup the most recent authority for a given frame. | |
std::vector< TimeCache * > | frames_ |
The pointers to potential frames that the tree can be made of. | |
Mutex * | frame_mutex_ |
A mutex to protect testing and allocating new frames on the above vector. | |
float | cache_time_ |
How long to cache transform history. | |
float | max_extrapolation_distance_ |
whether or not to allow extrapolation | |
std::string | tf_prefix_ |
transform prefix to apply as necessary | |
bool | fall_back_to_wall_time_ |
Set to true to allow falling back to wall time. |
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
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.
fawkes::tf::Transformer::Transformer | ( | float | cache_time = 10.0 | ) |
Constructor.
cache_time | time in seconds to cache incoming transforms |
Definition at line 267 of file transformer.cpp.
References max_extrapolation_distance_, DEFAULT_MAX_EXTRAPOLATION_DISTANCE, frameIDs_, frames_, frameIDs_reverse, and frame_mutex_.
fawkes::tf::Transformer::~Transformer | ( | void | ) | [virtual] |
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.
target_frame | The frame into which to transform |
source_frame | The frame from which to transform |
time | The time at which to transform |
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.
target_frame | The frame into which to transform |
target_time | The time into which to transform |
source_frame | The frame from which to transform |
source_time | The time from which to transform |
fixed_frame | The frame in which to treat the transform as constant in time |
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.
frame_id_str | frame ID |
Definition at line 325 of file transformer.cpp.
References frame_mutex_, and frameIDs_.
Referenced by get_latest_common_time(), can_transform(), 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
frame_number | The frameID of the desired reference frame |
LookupException | thrown if lookup fails |
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.
frame_id | frame ID |
LookupException | thrown if lookup fails |
Definition at line 784 of file transformer.cpp.
References lookup_frame_number(), and frames_.
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.
source_frame | source frame ID |
target_frame | frame target frame ID |
time | upon return contains latest common timestamp |
error_string | upon error contains accumulated error message. |
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.
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.
frameid_str | frame ID |
LookupException | if frame ID is unknown |
Definition at line 801 of file transformer.cpp.
References frameIDs_.
Referenced by get_latest_common_time(), get_frame_cache(), lookup_transform(), and can_transform().
std::string fawkes::tf::Transformer::lookup_frame_string | ( | unsigned int | frame_num | ) | const [protected] |
Get frame ID given its number.
frame_num | frame number |
LookupException | thrown 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.
frameid_str | frame ID |
Definition at line 824 of file transformer.cpp.
References frameIDs_, frames_, cache_time_, and frameIDs_reverse.
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.
target_frame | target frame ID |
source_frame | source frame ID |
time | time for which to get the transform, set to (0,0) to get latest common time frame |
transform | upon return contains the transform |
ConnectivityException | thrown if no connection between the source and target frame could be found in the tree. |
ExtrapolationException | returning a value would have required extrapolation beyond current limits. |
LookupException | at least one of the two given frames is unknown |
Definition at line 869 of file transformer.cpp.
References enabled_, fawkes::tf::StampedTransform::child_frame_id, fawkes::tf::StampedTransform::frame_id, fawkes::tf::StampedTransform::stamp, frame_mutex_, lookup_frame_number(), fawkes::tf::TransformAccum::result_vec, fawkes::tf::TransformAccum::result_quat, and fawkes::tf::TransformAccum::time.
Referenced by lookup_transform(), transform_quaternion(), transform_vector(), transform_point(), transform_pose(), TfExampleThread::loop(), LaserProjectionDataFilter::filter(), and TabletopObjectsThread::loop().
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.
target_frame | target frame ID |
source_frame | source frame ID |
transform | upon return contains the transform |
ConnectivityException | thrown if no connection between the source and target frame could be found in the tree. |
ExtrapolationException | returning a value would have required extrapolation beyond current limits. |
LookupException | at 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.
target_frame | target frame ID |
target_time | time for the target frame |
source_frame | source frame ID |
source_time | time in the source frame |
fixed_frame | ID of fixed frame |
transform | upon return contains the transform |
ConnectivityException | thrown if no connection between the source and target frame could be found in the tree. |
ExtrapolationException | returning a value would have required extrapolation beyond current limits. |
LookupException | at least one of the two given frames is unknown |
Definition at line 959 of file transformer.cpp.
References lookup_transform(), fawkes::tf::StampedTransform::set_data(), fawkes::tf::StampedTransform::stamp, fawkes::tf::StampedTransform::frame_id, and fawkes::tf::StampedTransform::child_frame_id.
void fawkes::tf::Transformer::set_enabled | ( | bool | enabled | ) |
Set transformer enabled or disabled.
enabled | true 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.
transform | transform to set |
authority | authority from which the transform was received. |
Definition at line 698 of file transformer.cpp.
References fawkes::tf::StampedTransform::stamp, fawkes::tf::StampedTransform::child_frame_id, fawkes::tf::StampedTransform::frame_id, frame_mutex_, lookup_or_insert_frame_number(), get_frame(), frames_, cache_time_, fawkes::tf::TimeCache::insert_data(), and frame_authority_.
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.
target_frame | frame into which to transform |
stamped_in | stamped point, defines source frame and time |
stamped_out | stamped output point in target_frame |
ConnectivityException | thrown if no connection between the source and target frame could be found in the tree. |
ExtrapolationException | returning a value would have required extrapolation beyond current limits. |
LookupException | at least one of the two given frames is unknown |
Definition at line 1122 of file transformer.cpp.
References lookup_transform(), fawkes::tf::Stamped::frame_id, fawkes::tf::Stamped::stamp, fawkes::tf::Stamped::set_data(), and fawkes::tf::StampedTransform::stamp.
Referenced by KatanaActThread::loop(), TabletopObjectsThread::loop(), and TabletopVisualizationThread::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.
target_frame | frame into which to transform |
target_time | desired time in the target frame |
stamped_in | stamped point, defines source frame and time |
fixed_frame | ID of fixed frame |
stamped_out | stamped output point in target_frame |
ConnectivityException | thrown if no connection between the source and target frame could be found in the tree. |
ExtrapolationException | returning a value would have required extrapolation beyond current limits. |
LookupException | at least one of the two given frames is unknown |
Definition at line 1265 of file transformer.cpp.
References lookup_transform(), fawkes::tf::Stamped::frame_id, fawkes::tf::Stamped::stamp, fawkes::tf::Stamped::set_data(), and fawkes::tf::StampedTransform::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.
target_frame | frame into which to transform |
stamped_in | stamped pose, defines source frame and time |
stamped_out | stamped output pose in target_frame |
ConnectivityException | thrown if no connection between the source and target frame could be found in the tree. |
ExtrapolationException | returning a value would have required extrapolation beyond current limits. |
LookupException | at least one of the two given frames is unknown |
Definition at line 1150 of file transformer.cpp.
References lookup_transform(), fawkes::tf::Stamped::frame_id, fawkes::tf::Stamped::stamp, fawkes::tf::Stamped::set_data(), and fawkes::tf::StampedTransform::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.
target_frame | frame into which to transform |
target_time | desired time in the target frame |
stamped_in | stamped pose, defines source frame and time |
fixed_frame | ID of fixed frame |
stamped_out | stamped output pose in target_frame |
ConnectivityException | thrown if no connection between the source and target frame could be found in the tree. |
ExtrapolationException | returning a value would have required extrapolation beyond current limits. |
LookupException | at least one of the two given frames is unknown |
Definition at line 1301 of file transformer.cpp.
References lookup_transform(), fawkes::tf::Stamped::frame_id, fawkes::tf::Stamped::stamp, fawkes::tf::Stamped::set_data(), and fawkes::tf::StampedTransform::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.
target_frame | frame into which to transform |
stamped_in | stamped quaternion, defines source frame and time |
stamped_out | stamped output quaternion in target_frame |
ConnectivityException | thrown if no connection between the source and target frame could be found in the tree. |
ExtrapolationException | returning a value would have required extrapolation beyond current limits. |
LookupException | at least one of the two given frames is unknown |
InvalidArgument | thrown if the Quaternion is invalid, most likely an uninitialized Quaternion (0,0,0,0). |
Definition at line 1061 of file transformer.cpp.
References lookup_transform(), fawkes::tf::Stamped::frame_id, fawkes::tf::Stamped::stamp, fawkes::tf::Stamped::set_data(), and fawkes::tf::StampedTransform::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.
target_frame | frame into which to transform |
target_time | desired time in the target frame |
stamped_in | stamped quaternion, defines source frame and time |
fixed_frame | ID of fixed frame |
stamped_out | stamped output quaternion in target_frame |
ConnectivityException | thrown if no connection between the source and target frame could be found in the tree. |
ExtrapolationException | returning a value would have required extrapolation beyond current limits. |
LookupException | at least one of the two given frames is unknown |
InvalidArgument | thrown if the Quaternion is invalid, most likely an uninitialized Quaternion (0,0,0,0). |
Definition at line 1186 of file transformer.cpp.
References lookup_transform(), fawkes::tf::Stamped::frame_id, fawkes::tf::Stamped::stamp, fawkes::tf::Stamped::set_data(), and fawkes::tf::StampedTransform::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.
target_frame | frame into which to transform |
stamped_in | stamped vector, defines source frame and time |
stamped_out | stamped output vector in target_frame |
ConnectivityException | thrown if no connection between the source and target frame could be found in the tree. |
ExtrapolationException | returning a value would have required extrapolation beyond current limits. |
LookupException | at least one of the two given frames is unknown |
Definition at line 1090 of file transformer.cpp.
References lookup_transform(), fawkes::tf::Stamped::frame_id, fawkes::tf::Stamped::stamp, fawkes::tf::Stamped::set_data(), and fawkes::tf::StampedTransform::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.
target_frame | frame into which to transform |
target_time | desired time in the target frame |
stamped_in | stamped vector, defines source frame and time |
fixed_frame | ID of fixed frame |
stamped_out | stamped output vector in target_frame |
ConnectivityException | thrown if no connection between the source and target frame could be found in the tree. |
ExtrapolationException | returning a value would have required extrapolation beyond current limits. |
LookupException | at least one of the two given frames is unknown |
Definition at line 1223 of file transformer.cpp.
References lookup_transform(), fawkes::tf::Stamped::frame_id, fawkes::tf::Stamped::stamp, fawkes::tf::Stamped::set_data(), and fawkes::tf::StampedTransform::stamp.
float fawkes::tf::Transformer::cache_time_ [protected] |
How long to cache transform history.
Definition at line 189 of file transformer.h.
Referenced by set_transform(), and lookup_or_insert_frame_number().
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 set_enabled(), and lookup_transform().
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_ [mutable, protected] |
A mutex to protect testing and allocating new frames on the above vector.
Definition at line 186 of file transformer.h.
Referenced by Transformer(), ~Transformer(), clear(), frame_exists(), set_transform(), lookup_transform(), and can_transform().
Map from frame IDs to frame numbers.
Definition at line 175 of file transformer.h.
Referenced by Transformer(), frame_exists(), lookup_frame_number(), and lookup_or_insert_frame_number().
Map from CompactFrameID frame_id_numbers to string for debugging and output.
Definition at line 177 of file transformer.h.
Referenced by Transformer(), lookup_or_insert_frame_number(), and lookup_frame_string().
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 Transformer(), ~Transformer(), clear(), set_transform(), get_frame(), get_frame_cache(), and lookup_or_insert_frame_number().
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.
static | const 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.