Using Python tf

Transformer

The Transformer object is the heart of tf. It maintains an internal time-varying graph of transforms, and permits asynchronous graph modification and queries. See the official documentation here.

Transformer does not handle ROS messages directly; the only ROS type it uses is rospy.Time(). Transformer also does not mandate any particular linear algebra library. Transformations involving ROS messages are done with TransformerROS (see below).

Transformer has the following methods:

* allFramesAsDot() -> string

Returns a string representing all frames

* allFramesAsString() -> string

Returns a string representing all frames

* setTransform(transform, authority)

Adds a new transform to the Transformer graph. The transform argument is an object with the following structure:

child_frame_id        string, child frame
header
    stamp             time stamp, rospy.Time
    frame_id          string, frame
transform
    translation
        x
        y
        z
    rotation
        x
        y
        z
        w

These members exactly match those of a ROS geometry_msgs/TransformStamped message.

* canTransform(target_frame, source_frame, time)

Returns True if the Transformer can determine the transform from source_frame to target_frame at the time time. time is a rospy.Time instance.

* canTransformFull(target_frame, target_time, source_frame, source_time, fixed_frame)

It's an extended version of canTransform.

* chain(target_frame, target_time, source_frame, source_time, fixed_frame) -> list

returns the chain of frames connecting source_frame to target_frame.

* frameExists(frame_id) -> Bool

returns True if frame frame_id exists in the Transformer`.

* getFrameStrings -> list

returns all frame names in the Transformer as a list.

* getLatestCommonTime(source_frame, target_frame) -> time

Determines that most recent time for which Transformer can compute the transform between the two given frames, that is, between source_frame and target_frame. Returns a rospy.Time.

* lookupTransform(target_frame, source_frame, time) -> position, quaternion

Returns the transform from source_frame to target_frame at the time time. time is a rospy.Time instance. The transform is returned as position (x, y, z) and an orientation quaternion (x, y, z, w).

* lookupTransformFull(target_frame, target_time, source_frame, source_time, fixed_frame)

It is the full version of lookupTransform.

Short example showing Transformer and setTransform:

import tf

t = tf.Transformer(True, rospy.Duration(10.0))
m = geometry_msgs.msg.TransformStamped()
m.header.frame_id = "THISFRAME"
m.parent_id = "PARENT"
t.setTransform(m)

A more exhaustive list of functions with examples can be found here.

TransformerROS and TransformListener

TransformerROS extends the base class Transformer, adding methods for handling ROS messages.

* asMatrix(target_frame, hdr) -> matrix

Looks up the transform for ROS message header hdr to frame target_frame, and returns the transform as a NumPy 4x4 matrix.

* fromTranslationRotation(translation, rotation) -> matrix

Returns a NumPy 4x4 matrix for a transform.

* transformPoint(target_frame, point_msg) -> point_msg

Transforms a geometry_msgs's PointStamped message, i.e. point_msg, to the frame target_frame, returns the resulting PointStamped.

* transformPose(target_frame, pose_msg) -> pose_msg

Transforms a geometry_msgs's PoseStamped message, i.e. point_msg, to the frame target_frame, returns the resulting PoseStamped.

* transformQuaternion(target_frame, quat_msg) -> quat_msg

Transforms a geometry_msgs's QuaternionStamped message, i.e. quat_msg, to the frame target_frame, returns the resulting QuaternionStamped.

TransformListener

TransformListener extends TransformerROS, adding a handler for ROS topic /tf_message, so that the messages update the transformer.

This example uses a TransformListener to find the current base_link position in the map.

import rospy
from tf import TransformListener

class myNode:

    def __init__(self, *args):
        self.tf = TransformListener()
        rospy.Subscriber(...)
        ...

    def some_method(self):
        if self.tf.frameExists("/base_link") and self.tf.frameExists("/map"):
            t = self.tf.getLatestCommonTime("/base_link", "/map")
            position, quaternion = self.tf.lookupTransform("/base_link", "/map", t)
            print position, quaternion

A simple example to transform a pose from one frame to another.

import rospy
import tf

class myNode:
    def __init__(self, *args):
        self.tf_listener_ = TransformListener()

    def example_function(self):
        if self.tf.frameExists("/base_link") and self.tf.frameExists("/fingertip"):
            t = self.tf_listener_.getLatestCommonTime("/base_link", "/fingertip")
            p1 = geometry_msgs.msg.PoseStamped()
            p1.header.frame_id = "fingertip"
            p1.pose.orientation.w = 1.0    # Neutral orientation
            p_in_base = self.tf_listener_.transformPose("/base_link", p1)
            print "Position of the fingertip in the robot base:"
            print p_in_base

transformations.py

The tf package also includes the popular transformations.py module. TransformerROS uses transformations.py to perform conversions between quaternions and matrices. transformations.py does useful conversions on NumPy matrices; it can convert between transformations as Euler angles, quaternions, and matrices.

Note: Euler angles are in radians in transformations.py.

Wiki: tf/TfUsingPython (last edited 2021-03-30 23:13:13 by TullyFoote)