tf (Python)

exception Exception

base class for tf exceptions. Because tf.Exception is the base class for other exceptions, you can catch all tf exceptions by writing:

try:
    # do some tf work
except tf.Exception:
    print "some tf exception happened"
exception ConnectivityException
subclass of Exception. Raised when that the fixed_frame tree is not connected between the frames requested.
exception LookupException
subclass of Exception. Raised when a tf method has attempted to access a frame, but the frame is not in the graph. The most common reason for this is that the frame is not being published, or a parent frame was not set correctly causing the tree to be broken.
exception ExtrapolationException
subclass of Exception Raised when a tf method would have required extrapolation beyond current limits.

Transformer

class tf.Transformer(interpolating, cache_time = rospy.Duration(10))
Parameters:
  • interpolating – Whether to interpolate transformations.
  • cache_time – how long tf should retain transformation information in the past.

The Transformer object is the core of tf. It maintains a time-varying graph of transforms, and permits asynchronous graph modification and queries:

>>> import rospy
>>> import tf
>>> import geometry_msgs.msg
>>> t = tf.Transformer(True, rospy.Duration(10.0))
>>> t.getFrameStrings()
[]
>>> m = geometry_msgs.msg.TransformStamped()
>>> m.header.frame_id = 'THISFRAME'
>>> m.child_frame_id = 'CHILD'
>>> m.transform.translation.x = 2.71828183
>>> m.transform.rotation.w = 1.0
>>> t.setTransform(m)
>>> t.getFrameStrings()
['/CHILD', '/THISFRAME']
>>> t.lookupTransform('THISFRAME', 'CHILD', rospy.Time(0))
((2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))
>>> t.lookupTransform('CHILD', 'THISFRAME', rospy.Time(0))
((-2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))

The transformer refers to frames using strings, and represents transformations using translation (x, y, z) and quaternions (x, y, z, w) expressed as Python a tuple. Transformer also does not mandate any particular linear algebra library. Transformer does not handle ROS messages directly; the only ROS type it uses is rospy.Time().

To use tf with ROS messages, see TransformerROS and TransformListener.

allFramesAsDot() → string
Returns a string representing all frames, intended for use with Graphviz.
allFramesAsString() → string
Returns a human-readable string representing all frames
setTransform(transform, authority = "")
Parameters:
  • transform – transform object, see below
  • authority – string giving authority for this transformation.

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

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

These members exactly match those of a ROS TransformStamped message.

waitForTransform(target_frame, source_frame, time, timeout, polling_sleep_duration = rospy.Duration(0.01))
Parameters:
  • target_frame – transformation target frame in tf, string
  • source_frame – transformation source frame in tf, string
  • time – time of the transformation, use rospy.Time() to indicate present time.
  • timeout – how long this call should block while waiting for the transform, as a rospy.Duration
Raises:

tf.Exception

Waits for the given transformation to become available. If the timeout occurs before the transformation becomes available, raises tf.Exception.

waitForTransformFull(target_frame, target_time, source_frame, source_time, fixed_frame)
Parameters:
  • target_frame – transformation target frame in tf, string
  • target_time – time of transformation in target_frame, a rospy.Time
  • source_frame – transformation source frame in tf, string
  • source_time – time of transformation in target_frame, a rospy.Time
  • fixed_frame – reference frame common to both target_frame and source_frame.
  • timeout – how long this call should block while waiting for the transform, as a rospy.Duration
Raises:

tf.Exception

Extended version of waitForTransform().

canTransform(target_frame, source_frame, time) → bool
Parameters:
  • target_frame – transformation target frame in tf, string
  • source_frame – transformation source frame in tf, string
  • time – time of the transformation, use rospy.Time() to indicate present time.

Returns True if the Transformer can determine the transform from source_frame to target_frame at time.

canTransformFull(target_frame, target_time, source_frame, source_time, fixed_frame) → bool
Extended version of canTransform().
chain(target_frame, target_time, source_frame, source_time, fixed_frame) → list
Parameters:
  • target_frame – transformation target frame in tf, string
  • target_time – time of transformation in target_frame, a rospy.Time
  • source_frame – transformation source frame in tf, string
  • source_time – time of transformation in target_frame, a rospy.Time
  • fixed_frame – reference frame common to both target_frame and source_frame.
Returns:

list of tf frames

Raises:

tf.ConnectivityException, tf.LookupException

returns the chain of frames connecting source_frame to target_frame.

clear() → None
Clear all transformations.
frameExists(frame_id) → Bool
Parameter:frame_id – a tf frame, string

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
Parameters:
  • target_frame – transformation target frame in tf, string
  • source_frame – transformation source frame in tf, string
Returns:

a rospy.Time for the most recent time at which the transform is available

Raises:

tf.Exception

Determines the most recent time for which Transformer can compute the transform between the two given frames. Raises tf.Exception if transformation is not possible.

lookupTransform(target_frame, source_frame, time) -> (position, quaternion)
Parameters:
  • target_frame – transformation target frame in tf, string
  • source_frame – transformation source frame in tf, string
  • time – time of the transformation, use rospy.Time() to indicate most recent common time.
Returns:

position as a translation (x, y, z) and orientation as a quaternion (x, y, z, w)

Raises:

tf.ConnectivityException, tf.LookupException, or tf.ExtrapolationException

Returns the transform from source_frame to target_frame at time. Raises one of the exceptions if the transformation is not possible.

Note that a time of zero means latest common time, so:

t.lookupTransform("a", "b", rospy.Time())

is equivalent to:

t.lookupTransform("a", "b", t.getLatestCommonTime("a", "b"))
lookupTransformFull(target_frame, target_time, source_frame, source_time, fixed_frame) → position, quaternion
Parameters:
  • target_frame – transformation target frame in tf, string
  • target_time – time of transformation in target_frame, a rospy.Time
  • source_frame – transformation source frame in tf, string
  • source_time – time of transformation in target_frame, a rospy.Time
  • fixed_frame – reference frame common to both target_frame and source_frame.
Raises:

tf.ConnectivityException, tf.LookupException, or tf.ExtrapolationException

Extended version of lookupTransform().

lookupTwist(tracking_frame, observation_frame, time, averaging_interval) → linear, angular
Parameters:
  • tracking_frame (str) – The frame to track
  • observation_frame (str) – The frame from which to measure the twist
  • time (rospy.Time) – The time at which to get the velocity
  • duration (rospy.Duration) – The period over which to average
Returns:

a tuple with linear velocity as (x, y, z) and angular velocity as (x, y, z)

Raises:

tf.ConnectivityException, tf.LookupException, or tf.ExtrapolationException

Simplified version of tf.lookupTwistFull().

Return the linear and angular velocity of the moving_frame in the reference_frame. tf considers time - duration / 2 to time + duration / 2 as the initial interval, and will shift by up to duration / 2 to avoid no data.

New in version 1.1.

lookupTwistFull(tracking_frame, observation_frame, reference_frame, reference_point, reference_point_frame, time, averaging_interval) → linear, angular
Parameters:
  • tracking_frame (str) – The frame to track
  • observation_frame (str) – The frame from which to measure the twist
  • reference_frame (str) – The reference frame in which to express the twist
  • reference_point (x, y, z) – The reference point with which to express the twist
  • reference_point_frame (str) – The frame_id in which the reference point is expressed
  • time (rospy.Time) – The time at which to get the velocity
  • duration (rospy.Duration) – The period over which to average
Returns:

a tuple with linear velocity as (x, y, z) and angular velocity as (x, y, z)

Raises:

tf.ConnectivityException, tf.LookupException, or tf.ExtrapolationException

Return the linear and angular velocity of the moving_frame in the reference_frame. tf considers time - duration / 2 to time + duration / 2 as the initial interval, and will shift by up to duration / 2 to avoid no data.

New in version 1.1.

getTFPrefix() → str
Returns:the TF Prefix that the transformer is running with

Returns the tf_prefix this transformer is running with.

TransformerROS

TransformListener

TransformBroadcaster

Table Of Contents

Previous topic

tf

This Page