Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Protected Attributes | List of all members
tf::Transformer Class Reference

A Class which provides coordinate transforms between any two frames in a system. More...

#include <tf.h>

Inheritance diagram for tf::Transformer:
Inheritance graph
[legend]

Public Member Functions

boost::signals2::connection addTransformsChangedListener (boost::function< void(void)> callback)
 Add a callback that happens when a new transform has arrived. More...
 
std::string allFramesAsDot (double current_time=0) const
 A way to see what frames have been cached Useful for debugging. More...
 
std::string allFramesAsString () const
 A way to see what frames have been cached Useful for debugging. More...
 
bool canTransform (const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, std::string *error_msg=NULL) const
 Test if a transform is possible. More...
 
bool canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
 Test if a transform is possible. More...
 
void chainAsVector (const std::string &target_frame, ros::Time target_time, const std::string &source_frame, ros::Time source_time, const std::string &fixed_frame, std::vector< std::string > &output) const
 Debugging function that will print the spanning chain of transforms. Possible exceptions tf::LookupException, tf::ConnectivityException, tf::MaxDepthException. More...
 
void clear ()
 Clear all data. More...
 
bool frameExists (const std::string &frame_id_str) const
 Check if a frame exists in the tree. More...
 
ros::Duration getCacheLength ()
 Get the duration over which this transformer will cache. More...
 
void getFrameStrings (std::vector< std::string > &ids) const
 A way to get a std::vector of available frame ids. More...
 
int getLatestCommonTime (const std::string &source_frame, const std::string &target_frame, ros::Time &time, std::string *error_string) const
 Return the latest rostime which is common across the spanning set zero if fails to cross. More...
 
bool getParent (const std::string &frame_id, ros::Time time, std::string &parent) const
 Fill the parent of a frame. More...
 
std::shared_ptr< tf2_ros::BuffergetTF2BufferPtr ()
 
std::string getTFPrefix () const
 Get the tf_prefix this is running with. More...
 
bool isUsingDedicatedThread ()
 
void lookupTransform (const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
 Get the transform between two frames by frame ID assuming fixed frame. More...
 
void lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
 Get the transform between two frames by frame ID. More...
 
void lookupTwist (const std::string &tracking_frame, const std::string &observation_frame, const ros::Time &time, const ros::Duration &averaging_interval, geometry_msgs::Twist &twist) const
 lookup the twist of the tracking frame with respect to the observational frame More...
 
void lookupTwist (const std::string &tracking_frame, const std::string &observation_frame, const std::string &reference_frame, const tf::Point &reference_point, const std::string &reference_point_frame, const ros::Time &time, const ros::Duration &averaging_interval, geometry_msgs::Twist &twist) const
 Lookup the twist of the tracking_frame with respect to the observation frame in the reference_frame using the reference point. More...
 
void removeTransformsChangedListener (boost::signals2::connection c)
 
void setExtrapolationLimit (const ros::Duration &distance)
 Set the distance which tf is allow to extrapolate. More...
 
bool setTransform (const StampedTransform &transform, const std::string &authority="default_authority")
 Add transform information to the tf data structure. More...
 
void setUsingDedicatedThread (bool value)
 
 Transformer (bool interpolating=true, ros::Duration cache_time_=ros::Duration(DEFAULT_CACHE_TIME))
 
void transformPoint (const std::string &target_frame, const ros::Time &target_time, const Stamped< tf::Point > &stamped_in, const std::string &fixed_frame, Stamped< tf::Point > &stamped_out) const
 Transform a Stamped Point into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformPoint (const std::string &target_frame, const Stamped< tf::Point > &stamped_in, Stamped< tf::Point > &stamped_out) const
 Transform a Stamped Point into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformPose (const std::string &target_frame, const ros::Time &target_time, const Stamped< tf::Pose > &stamped_in, const std::string &fixed_frame, Stamped< tf::Pose > &stamped_out) const
 Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformPose (const std::string &target_frame, const Stamped< tf::Pose > &stamped_in, Stamped< tf::Pose > &stamped_out) const
 Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformQuaternion (const std::string &target_frame, const ros::Time &target_time, const Stamped< tf::Quaternion > &stamped_in, const std::string &fixed_frame, Stamped< tf::Quaternion > &stamped_out) const
 Transform a Stamped Quaternion into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformQuaternion (const std::string &target_frame, const Stamped< tf::Quaternion > &stamped_in, Stamped< tf::Quaternion > &stamped_out) const
 Transform a Stamped Quaternion into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformVector (const std::string &target_frame, const ros::Time &target_time, const Stamped< tf::Vector3 > &stamped_in, const std::string &fixed_frame, Stamped< tf::Vector3 > &stamped_out) const
 Transform a Stamped Vector3 into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
void transformVector (const std::string &target_frame, const Stamped< tf::Vector3 > &stamped_in, Stamped< tf::Vector3 > &stamped_out) const
 Transform a Stamped Vector3 into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument. More...
 
bool waitForTransform (const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
 Block until a transform is possible or it times out. More...
 
bool waitForTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
 Block until a transform is possible or it times out. More...
 
virtual ~Transformer (void)
 

Public Attributes

bool fall_back_to_wall_time_
 

Static Public Attributes

static const double DEFAULT_CACHE_TIME = 10.0
 10.0 is the default amount of time to cache data in seconds, set in cpp file. More...
 
static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0ULL
 The default amount of time to extrapolate //deprecated since integration with tf2. More...
 
static const unsigned int MAX_GRAPH_DEPTH = 100UL
 The maximum number of time to recurse before assuming the tree has a loop. More...
 

Protected Member Functions

ros::Time now () const
 
virtual bool ok () const
 

Protected Attributes

std::shared_ptr< tf2_ros::Buffertf2_buffer_ptr_
 
std::string tf_prefix_
 The internal storage class for ReferenceTransform. More...
 

Detailed Description

A Class which provides 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.

libTF 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. libTF is designed to take care of all the intermediate steps for you.

Internal Representation libTF 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 tf::LookupException

Definition at line 103 of file tf.h.

Constructor & Destructor Documentation

◆ Transformer()

Transformer::Transformer ( bool  interpolating = true,
ros::Duration  cache_time_ = ros::Duration(DEFAULT_CACHE_TIME) 
)

Constructor

Parameters
interpolatingUnused, legacy always true
cache_timeHow long to keep a history of transforms in nanoseconds

Definition at line 209 of file tf.cpp.

◆ ~Transformer()

Transformer::~Transformer ( void  )
virtual

Definition at line 217 of file tf.cpp.

Member Function Documentation

◆ addTransformsChangedListener()

boost::signals2::connection Transformer::addTransformsChangedListener ( boost::function< void(void)>  callback)

Add a callback that happens when a new transform has arrived.

Parameters
callbackThe callback, of the form void func();
Returns
A boost::signals2::connection object that can be used to remove this listener

Definition at line 573 of file tf.cpp.

◆ allFramesAsDot()

std::string Transformer::allFramesAsDot ( double  current_time = 0) const

A way to see what frames have been cached Useful for debugging.

Definition at line 439 of file tf.cpp.

◆ allFramesAsString()

std::string Transformer::allFramesAsString ( ) const

A way to see what frames have been cached Useful for debugging.

Definition at line 434 of file tf.cpp.

◆ canTransform() [1/2]

bool Transformer::canTransform ( const std::string &  target_frame,
const ros::Time target_time,
const std::string &  source_frame,
const ros::Time source_time,
const std::string &  fixed_frame,
std::string *  error_msg = NULL 
) 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
error_msgA pointer to a string which will be filled with why the transform failed, if not NULL

Definition at line 366 of file tf.cpp.

◆ canTransform() [2/2]

bool Transformer::canTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time,
std::string *  error_msg = NULL 
) 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
error_msgA pointer to a string which will be filled with why the transform failed, if not NULL

Definition at line 358 of file tf.cpp.

◆ chainAsVector()

void Transformer::chainAsVector ( const std::string &  target_frame,
ros::Time  target_time,
const std::string &  source_frame,
ros::Time  source_time,
const std::string &  fixed_frame,
std::vector< std::string > &  output 
) const

Debugging function that will print the spanning chain of transforms. Possible exceptions tf::LookupException, tf::ConnectivityException, tf::MaxDepthException.

Debugging function that will print the spanning chain of transforms. Possible exceptions tf::LookupException, tf::ConnectivityException, tf::MaxDepthException

Definition at line 427 of file tf.cpp.

◆ clear()

void Transformer::clear ( )

Clear all data.

Definition at line 223 of file tf.cpp.

◆ frameExists()

bool Transformer::frameExists ( const std::string &  frame_id_str) const

Check if a frame exists in the tree.

Parameters
frame_id_strThe frame id in question

Definition at line 392 of file tf.cpp.

◆ getCacheLength()

ros::Duration tf::Transformer::getCacheLength ( )
inline

Get the duration over which this transformer will cache.

Definition at line 331 of file tf.h.

◆ getFrameStrings()

void Transformer::getFrameStrings ( std::vector< std::string > &  ids) const

A way to get a std::vector of available frame ids.

Definition at line 447 of file tf.cpp.

◆ getLatestCommonTime()

int Transformer::getLatestCommonTime ( const std::string &  source_frame,
const std::string &  target_frame,
ros::Time time,
std::string *  error_string 
) const

Return the latest rostime which is common across the spanning set zero if fails to cross.

Definition at line 417 of file tf.cpp.

◆ getParent()

bool Transformer::getParent ( const std::string &  frame_id,
ros::Time  time,
std::string &  parent 
) const

Fill the parent of a frame.

Parameters
frame_idThe frame id of the frame in question
parentThe reference to the string to fill the parent Returns true unless "NO_PARENT"

Definition at line 386 of file tf.cpp.

◆ getTF2BufferPtr()

std::shared_ptr<tf2_ros::Buffer> tf::Transformer::getTF2BufferPtr ( )
inline

Definition at line 354 of file tf.h.

◆ getTFPrefix()

std::string tf::Transformer::getTFPrefix ( ) const
inline

Get the tf_prefix this is running with.

Definition at line 346 of file tf.h.

◆ isUsingDedicatedThread()

bool tf::Transformer::isUsingDedicatedThread ( )
inline

Definition at line 351 of file tf.h.

◆ lookupTransform() [1/2]

void Transformer::lookupTransform ( const std::string &  target_frame,
const ros::Time target_time,
const std::string &  source_frame,
const ros::Time source_time,
const std::string &  fixed_frame,
StampedTransform transform 
) const

Get the transform between two frames by frame ID assuming fixed frame.

Parameters
target_frameThe frame to which data should be transformed
target_timeThe time to which the data should be transformed. (0 will get the latest)
source_frameThe frame where the data originated
source_timeThe time at which the source_frame should be evaluated. (0 will get the latest)
fixed_frameThe frame in which to assume the transform is constant in time.
transformThe transform reference to fill.

Possible exceptions tf::LookupException, tf::ConnectivityException, tf::MaxDepthException, tf::ExtrapolationException

Definition at line 249 of file tf.cpp.

◆ lookupTransform() [2/2]

void Transformer::lookupTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time,
StampedTransform transform 
) const

Get the transform between two frames by frame ID.

Parameters
target_frameThe frame to which data should be transformed
source_frameThe frame where the data originated
timeThe time at which the value of the transform is desired. (0 will get the latest)
transformThe transform reference to fill.

Possible exceptions tf::LookupException, tf::ConnectivityException, tf::MaxDepthException, tf::ExtrapolationException

Definition at line 238 of file tf.cpp.

◆ lookupTwist() [1/2]

void Transformer::lookupTwist ( const std::string &  tracking_frame,
const std::string &  observation_frame,
const ros::Time time,
const ros::Duration averaging_interval,
geometry_msgs::Twist &  twist 
) const

lookup the twist of the tracking frame with respect to the observational frame

This is a simplified version of lookupTwist with it assumed that the reference point is the origin of the tracking frame, and the reference frame is the observation frame.

New in geometry 1.1

Definition at line 260 of file tf.cpp.

◆ lookupTwist() [2/2]

void Transformer::lookupTwist ( const std::string &  tracking_frame,
const std::string &  observation_frame,
const std::string &  reference_frame,
const tf::Point reference_point,
const std::string &  reference_point_frame,
const ros::Time time,
const ros::Duration averaging_interval,
geometry_msgs::Twist &  twist 
) const

Lookup the twist of the tracking_frame with respect to the observation frame in the reference_frame using the reference point.

Parameters
tracking_frameThe frame to track
observation_frameThe frame from which to measure the twist
reference_frameThe reference frame in which to express the twist
reference_pointThe reference point with which to express the twist
reference_point_frameThe frame_id in which the reference point is expressed
timeThe time at which to get the velocity
durationThe period over which to average
twistThe twist output

This will compute the average velocity on the interval (time - duration/2, time+duration/2). If that is too close to the most recent reading, in which case it will shift the interval up to duration/2 to prevent extrapolation. Possible exceptions tf::LookupException, tf::ConnectivityException, tf::MaxDepthException, tf::ExtrapolationException

New in geometry 1.1

\TODO check time on reference point too

Definition at line 270 of file tf.cpp.

◆ now()

ros::Time tf::Transformer::now ( ) const
inlineprotected

Hack method to work around #4150

Definition at line 384 of file tf.h.

◆ ok()

bool Transformer::ok ( ) const
protectedvirtual

Reimplemented in tf::TransformListener.

Definition at line 445 of file tf.cpp.

◆ removeTransformsChangedListener()

void Transformer::removeTransformsChangedListener ( boost::signals2::connection  c)

Definition at line 578 of file tf.cpp.

◆ setExtrapolationLimit()

void Transformer::setExtrapolationLimit ( const ros::Duration distance)

Set the distance which tf is allow to extrapolate.

Parameters
distanceHow far to extrapolate before throwing an exception default is zero

Definition at line 397 of file tf.cpp.

◆ setTransform()

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

Add transform information to the tf data structure.

Parameters
transformThe transform to store
authorityThe source of the information for this transform returns true unless an error occured

Definition at line 229 of file tf.cpp.

◆ setUsingDedicatedThread()

void tf::Transformer::setUsingDedicatedThread ( bool  value)
inline

Definition at line 349 of file tf.h.

◆ transformPoint() [1/2]

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

Transform a Stamped Point into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Definition at line 543 of file tf.cpp.

◆ transformPoint() [2/2]

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

Transform a Stamped Point into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Definition at line 484 of file tf.cpp.

◆ transformPose() [1/2]

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

Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Definition at line 558 of file tf.cpp.

◆ transformPose() [2/2]

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

Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Definition at line 494 of file tf.cpp.

◆ transformQuaternion() [1/2]

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

Transform a Stamped Quaternion into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Definition at line 505 of file tf.cpp.

◆ transformQuaternion() [2/2]

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

Transform a Stamped Quaternion into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Definition at line 453 of file tf.cpp.

◆ transformVector() [1/2]

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

Transform a Stamped Vector3 into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

◆ transformVector() [2/2]

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

Transform a Stamped Vector3 into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument.

Todo:
may not be most efficient

Definition at line 466 of file tf.cpp.

◆ waitForTransform() [1/2]

bool Transformer::waitForTransform ( const std::string &  target_frame,
const ros::Time target_time,
const std::string &  source_frame,
const ros::Time source_time,
const std::string &  fixed_frame,
const ros::Duration timeout,
const ros::Duration polling_sleep_duration = ros::Duration(0.01),
std::string *  error_msg = NULL 
) const

Block until a transform is possible or it times out.

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
timeoutHow long to block before failing
polling_sleep_durationHow often to retest if failed
error_msgA pointer to a string which will be filled with why the transform failed, if not NULL

Definition at line 375 of file tf.cpp.

◆ waitForTransform() [2/2]

bool Transformer::waitForTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time,
const ros::Duration timeout,
const ros::Duration polling_sleep_duration = ros::Duration(0.01),
std::string *  error_msg = NULL 
) const

Block until a transform is possible or it times out.

Parameters
target_frameThe frame into which to transform
source_frameThe frame from which to transform
timeThe time at which to transform
timeoutHow long to block before failing
polling_sleep_durationHow often to retest if failed
error_msgA pointer to a string which will be filled with why the transform failed, if not NULL

Definition at line 348 of file tf.cpp.

Member Data Documentation

◆ DEFAULT_CACHE_TIME

const double tf::Transformer::DEFAULT_CACHE_TIME = 10.0
static

10.0 is the default amount of time to cache data in seconds, set in cpp file.

Definition at line 108 of file tf.h.

◆ DEFAULT_MAX_EXTRAPOLATION_DISTANCE

const int64_t tf::Transformer::DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0ULL
static

The default amount of time to extrapolate //deprecated since integration with tf2.

Definition at line 109 of file tf.h.

◆ fall_back_to_wall_time_

bool tf::Transformer::fall_back_to_wall_time_

Definition at line 380 of file tf.h.

◆ MAX_GRAPH_DEPTH

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

The maximum number of time to recurse before assuming the tree has a loop.

Definition at line 107 of file tf.h.

◆ tf2_buffer_ptr_

std::shared_ptr<tf2_ros::Buffer> tf::Transformer::tf2_buffer_ptr_
protected

Definition at line 403 of file tf.h.

◆ tf_prefix_

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

The internal storage class for ReferenceTransform.

An instance of this class is created for each frame in the system. This class natively handles the relationship between frames.

The derived class Pose3DCache provides a buffered history of positions with interpolation. transform prefix to apply as necessary

Definition at line 375 of file tf.h.


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


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sat Aug 19 2023 02:38:08