[Documentation] [TitleIndex] [WordIndex

geometry: angles | eigen_conversions | tf | tf_conversions

Package Summary

tf is a package that lets the user keep track of multiple coordinate frames over time. tf maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.

frames2.png

What does tf do? Why should I use tf?

You want to see what tf can do instead of just reading about it? Check out the tf introduction demo.

A robotic system typically has many 3D coordinate frames that change over time, such as a world frame, base frame, gripper frame, head frame, etc. tf keeps track of all these frames over time, and allows you to ask questions like:

tf can operate in a distributed system. This means all the information about the coordinate frames of a robot is available to all ROS components on any computer in the system. There is no central server of transform information.

For more information on the design see /Design

Tutorials

We created a set of tutorials that walk you through using tf, step by step. You can get started on the introduction to tf tutorial. For a complete list of all tf and tf-related tutorials check out the tutorials page.

There are essentially two tasks that any user would use tf for, listening for transforms and broadcasting transforms.

Anyone using tf will need to listen for transforms:

To extend the capabilities of a robot you will need to start broadcasting transforms.

Once you are finished with the basic tutorials, you can move on to learn about tf and time. The tf and time tutorial (Python) (C++) teaches the basic principles of tf and time. The advanced tutorial about tf and time (Python) (C++) teaches the principles of time traveling with tf.

Code API Overview

Frequently asked questions

Command-line Tools

Although tf is mainly a code library meant to be used within ROS nodes, it comes with a large set of command-line tools that assist in the debugging and creation of tf coordinate frames. These tools include:

You may also wish to use the tf_remap node, which is a utility node for remapping coordinate transforms.

tf_monitor

tf_monitor

$ rosrun tf tf_monitor
RESULTS: for all Frames

Frames:
Frame: /base_footprint published by /robot_pose_ekf Average Delay: 0.0469324 Max Delay: 0.0501503
Frame: /base_laser_link published by /robot_state_publisher Average Delay: 0.00891066 Max Delay: 0.009591
Frame: /base_link published by /robot_state_publisher Average Delay: 0.00891147 Max Delay: 0.009592
0.00891431 Max Delay: 0.009595

... editing for the sake of brevity ...

Broadcasters:
Node: /realtime_loop 94.7371 Hz, Average Delay: 0.000599916 Max Delay: 0.001337
Node: /robot_pose_ekf 30.8259 Hz, Average Delay: 0.0469324 Max Delay: 0.0501503
Node: /robot_state_publisher 25.8099 Hz, Average Delay: 0.0089224 Max Delay: 0.00960276

tf_monitor <source_frame> <target_target>

$ rosrun tf tf_monitor /base_footprint /odom
RESULTS: for /base_footprint to /odom
Chain currently is: /base_footprint -> /odom
Net delay     avg = 0.00371811: max = 0.012472

Frames:
Frame: /base_footprint published by /robot_pose_ekf Average Delay: 0.0465218 Max Delay: 0.051754
Frame: /odom published by /realtime_loop Average Delay: 0.00062444 Max Delay: 0.001553

Broadcasters:
Node: /realtime_loop 95.3222 Hz, Average Delay: 0.00062444 Max Delay: 0.001553
Node: /robot_pose_ekf 30.9654 Hz, Average Delay: 0.0465218 Max Delay: 0.051754
Node: /robot_state_publisher 25.9839 Hz, Average Delay: 0.00903061 Max Delay: 0.00939562

tf_echo

tf_echo <source_frame> <target_frame>

$ rosrun tf tf_echo /map /odom
At time 1263248513.809
- Translation: [2.398, 6.783, 0.000]
- Rotation: in Quaternion [0.000, 0.000, -0.707, 0.707]
in RPY [0.000, -0.000, -1.570]

static_transform_publisher

static_transform_publisher x y z yaw pitch roll frame_id child_frame_id period_in_ms

static_transform_publisher x y z qx qy qz qw frame_id child_frame_id  period_in_ms

static_transform_publisher is designed both as a command-line tool for manual use, as well as for use within roslaunch files for setting static transforms. For example:

   1 <launch>
   2 <node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="1 0 0 0 0 0 link1_parent link1 100" />
   3 </launch>

view_frames

view_frames

You probably want to view the graph when you are done, so a typical usage on Ubuntu systems is:

$ rosrun tf view_frames
$ evince frames.pdf

roswtf plugin

roswtf tf comes with a plugin for roswtf that automatically runs whenever you run roswtf. This plugin will analyze your current tf configuration and attempt to find common problems. To run, just invoke roswtf normally:

$ roswtf

Nodes

tf_remap

tf_remap listens to the /tf_old topic and republishes transforms on the /tf topic. This is mainly used with out-of-date bag files that need their coordinate frame IDs updated. The typical operation for this node is to play the bag file with /tf:=/old_tf. The tf_remap node is run with a ~mappings parameter that describes the mapping of frame IDs from old to new.

Subscribed Topics

/tf_old (tf/tfMessage)

Published Topics

/tf (tf/tfMessage)

Parameters

~mappings ([ {str: str} ], default: [])

change_notifier

change_notifier listens to /tf and periodically republishes any transforms that have changed by a given amount on the /tf_changes topic.

Subscribed Topics

/tf (tf/tfMessage)

Published Topics

/tf_changes (tf/tfMessage)

Parameters

~polling_frequency (float, default: 10.0) ~translational_update_distance (float, default: 0.1) ~angular_update_distance (float, default: 0.1)

# Keywords Transformation, Transformations, coordinate transform


2011-11-19 12:36