The Inner Workings of TF

The tf package keeps track of coordinate frames in distributed system.

Each process that has primary knowledge about the relationship between two coordinate frames broadcasts the relative transform for each pair of frames between which they have primary knowledge. Any process that wants information about coordinate frame transforms listens for all the broadcasts on the system and caches the received data. When a transform between two specific coordinate frames is requested, tf uses the cached information to determine the minimum spanning set of transforms to get between the requested frames. From this set of transforms it can compose the net transform between the requested frames.

To leverage this as a system all data in ROS is tagged with the frame id in which it collected. The tf library provides helper functions that take in a basic data type tagged with a frame id, (such as a point, vector, point cloud, orientation, or pose), and the target frame id, and returns the transformed data in the coordinate frame associated with the target frame id. This allows the programmer to easily use any data in whichever coordinate frame is most convenient, while only one copy of the data is generated and distributed to potentially many consumers.

tf was developed specifically to work in the ROS architecture, but it can also be used in a standalone manner. Although it has not been packaged for standalone distribution, all tf requires is some headers from other packages.

tf leverages the open source Bullet Physics linear algebra classes and methods.

To help with debugging a 3D visualization of all the coordinate frames with names and arrows to the parent coordinate frame can be viewed in the rviz package. The visual display allows not only the structure to be viewed but make understanding a series of transforms much easier. The visualizer includes both the 3D accelerated view of the transforms in space as well as numeric readouts of each of the transforms values.

tf_prefixes

frame_ids used with tf follow a limited subset of this naming conventions.

  • Prefixes are set using the parameter ~tf_prefix in each node.
  • The depth of the prefixes can only be one deep. Which means that :
    • There is no support for private names, indicated by '~'
    • "Pushing Down" is not possible

Transformer Library

The tf::Transformer class is a ROS-indepdent library. Its design, implementation and rationale are described below.

Storage

Transforms are expressed as a combination of a translation and rotation in 3D space, in the form of a tf::Vector3 and a tf::Quaternion. Each transform has an associated frame id, parent id, and time stamp. Each transform added to the library is pushed into a list sorted by time for each frame id.

Transform Composition

To generate a transform between two arbitrary frames, the structure of the relationship between the frames is assumed to be a tree. To find the spanning set between any two frames, tf starts by recursively finding the parent of both the target frame and the source frame. These will both end at the root of the tree. tf then steps back down the tree and removes all but the closest common parent.

Transforms in Time

It is often useful to know where an object is in relation to something at a different time. Data is timestamped when observed, however it is often used at a non negligable time later than when it was observed. To handle this the tf API provide an advanced form of each method which can transform a Stamped piece of data from it's observed frame and time into a different frame at a different time. This is only possible if there exists a frame in which the object is expected not to move relative to during the period between the starting time and the ending time. This frame is explicitly passed in the function calls for it will vary based on the context. For example when building a local map using the odometric frame as a fixed frame is usually the most accurate, while when working with navigational landmarks and loop closures a map based frame will be more accurate. Or if an object is currently being held in the gripper the gripper frame is the best frame to declare as the fixed frame.

A very common example is an object observed as a vehicle is driving. Two seconds later as the vehicle approaches the obstacle, the navigation algorithms would like to know where the object is in relation to the vehicle. To provide this a tf user would call the advanced version of the API with the odometric frame as the fixed frame. The source frame and time would have been set by the data source, and the target frame would be set to the vehicle frame and the time requested could either be "now" or "latest". Tf's response will be to transform the data at the time it was observed into the fixed frame. It will then jump the timestamp to the target_time. After jumping the timestamp to the target time the transform from the fixed frame to the target frame is computed. Thus tf can effectively transform data in time.

An accurate choice of the fixed frame is a required for validity of this method. The above choice of the odometric frame would be incorrect if the vehicle had a robotic hand which grabbed the object when it was observed. Two seconds after grabbing the object, it would be in the same position with relation to the hand, and and not the vehicle, so the fixed frame would be hand. And the lookup would show the position of the object in the body frame the same distance from the hand as observed when picked up, but the position of the hand may have changed relative to the body in the two seconds, to which this would be robust.

Exceptions

Exceptions are thrown for bad lookup requests and malformed trees. The exceptions all derive from tf::TransformException, which is a subclass of std::RuntimeError and have the method what() defined for debugging. The specific exception classes are tf::LookupException, tf::MaxDepthException and tf::ConnectivityException.

Timing is also important to tf, so there a tf::ExtrapolationException that is thrown in cases when the time requested is too far from data currently stored in the library. There are two common cases when this would happen. If requests are made of tf faster than new transforms are added, it will complain. The other case is if the requested time is too far in the past to be in the list of transforms stored. The tf::Transformer constructor allows you to configure the amount of extrapolation and how long to keep data.

Computation

tf does not do any background processing. All transforms are generated when requested and transform lists are updated during the inserting function call. Transform updates simply prune expired transforms from the end of the list.

All interfaces use the std::string representation of the frame id, although these strings are mapped to numerical ids interally to avoid calculations with strings.

Wiki: tf/Theory (last edited 2010-04-20 04:13:18 by PatrickBouffard)