Contents
Note: for the Python interface, see tf/TfUsingPython
TransformListener
For most purposes using tf will be done using the tf::TransformListener. It inherits several methods from tf::Transformer The primary methods which should be used when interacting with a tf::TransformListener are listed here:
Constructors
1 TransformListener(const ros::NodeHandle &nh, ros::Duration max_cache_time=ros::Duration(DEFAULT_CACHE_TIME), bool spin_thread=true)
1 TransformListener(ros::Duration max_cache_time=ros::Duration(DEFAULT_CACHE_TIME), bool spin_thread=true)
Helper methods
1 std::string tf::TransformListener::resolve (const std::string &frame_id)
Determine the fully resolved frame_id obeying the tf_prefix. See geometry/CoordinateFrameConventions.
canTransform()
The canTransform() methods return a bool whether the transform can be evaluated. It will not throw. If you pass a non NULL string pointer it will fill the string error_msg in the case of an error.
NOTE: this takes notably more resources to generate the error message.
Basic API
1 bool tf::TransformListener::canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
Test if source_frame can be transformed to target_frame at time time.
Advanced API
1 bool tf::TransformListener::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 source_frame can be transformed to fixed_frame at time source_time, and from there can be tranformed into target_frame at target_time.
waitForTransform
Basic API
1 bool tf::TransformListener::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
Test if source_frame can be transformed to target_frame at time time.
The waitForTransform() methods return a bool whether the transform can be evaluated. It will sleep and retry every polling_duration until the duration of timeout has been passed. It will not throw. If you pass a non NULL string pointer it will fill the string error_msg in the case of an error. (Note: That this takes notably more resources to generate the error message.)
Advanced API
1 bool tf::TransformListener::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
Test if source_frame can be transformed to fixed_frame at time source_time, and from there can be transformed into target_frame at target_time.
lookupTransform
lookupTransform() is a lower level method which returns the transform between two coordinate frames. This method is the core functionality of the tf library, however most often the transform* methods will be used by the end user. This methods is designed to be used within transform*() methods.
The direction of the transform returned will be from the target_frame to the source_frame. Which if applied to data, will transform data in the source_frame into the target_frame. See geometry/CoordinateFrameConventions#Transform_Direction
This may throw any tf exception
Basic API
1 void tf::TransformListener::lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
Fill transform with the transform from source_frame to target_frame at time.
Advanced API
1 void tf::TransformListener::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
Fill transform with the transform from source_frame to fixed_frame at source_time, chained with the transform from fixed_frame to target_frame at target_time
transformDATA Methods
The tf::TransformListener's main purpose is to transform data between coordinate frames. Below are the two primary prototypes.
Supported Data Types
C++ Method Name |
Python Method Name |
Full Datatype |
transformQuaternion() |
none |
tf::Stamped<tf::Quaternion> |
transformVector() |
none |
tf::Stamped<tf::Vector3> |
transformPoint() |
none |
tf::Stamped<tf::Point> |
transformPose() |
none |
tf::Stamped<tf::Pose> |
transformQuaternion() |
transformQuaternion() |
|
transformVector() |
transformVector3() |
|
transformPoint() |
transformPoint() |
|
transformPose() |
transformPose() |
|
transformPointCloud() |
transformPointCloud() |
Basic API
C++
1 void tf::TransformListener::transformDATATYPE (const std::string &target_frame, const geometry_msgs::DATATYPEStamped &stamped_in, geometry_msgs::DATATYPEStamped &stamped_out) const
Transform the data stamped_in into the target_frame, using the frame_id and stamp inside the stamped datatype as the source.
Python
1 TransformListener.transformDATATYPE (target_frame, stamped_in)
Return a new DATATYPE representing stamped_in transformed into target_frame
stamped_in is of type DATATYPE
target_frame is a string
Advanced API
1 void tf::TransformListener::transformDATATYPE (const std::string &target_frame, const ros::Time &target_time, const geometry_msgs::DATATYPEStamped &pin, const std::string &fixed_frame, geometry_msgs::DATATYPEStamped &pout) const
Transform the data stamped_in into the fixed_frame. Using the frame_id and stamp inside the stamped datatype as the source. Then transform from the fixed_frame into the target_frame at the target_time.