[Documentation] [TitleIndex] [WordIndex

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)

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 

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 

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 

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 

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 

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 

C++ Tutorial Python Tutorial

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()

geometry_msgs/QuaternionStamped

transformVector()

transformVector3()

geometry_msgs/Vector3Stamped

transformPoint()

transformPoint()

geometry_msgs/PointStamped

transformPose()

transformPose()

geometry_msgs/PoseStamped

transformPointCloud()

transformPointCloud()

sensor_msgs/PointCloud

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 

Python

   1 TransformListener.transformDATATYPE (target_frame, stamped_in) 

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 

2024-04-13 13:11