Using Python tf
Contents
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.
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, 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. transform is an object with the following structure:
parent_id string, parent frame
header
stamp time stamp, rospy.Time
frame_id string, frame
transform
translation
x
y
z
rotation
x
y
z
wThese 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 time. time is rospy.Time
canTransformFull(target_frame, target_time, source_frame, source_time, fixed_frame)
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. Returns a rospy.Time.
lookupTransform(target_frame, source_frame, time) -> position, quaternion
Returns the transform from source_frame to target_frame at time. time is a rospy.Time. The transform is returned as position (x,y,z) and an orientation quaternion (x,y,z,w).
lookTransformFull(target_frame, target_time, source_frame, source_time, fixed_frame)
Full version of lookupTransform.
Short example showing Transformer and setTransform:
import tf t = tf.Transformer(True, rospy.Duration(10.0)) m = robot_msgs.msg.TransformStamped() m.header.frame_id = "THISFRAME" m.parent_id = "PARENT" t.setTransform(m)
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 PointStamped message to frame target_frame, returns the resulting PointStamped.
transformPose(target_frame, pose_msg) -> pose_msg
Transforms a geometry_msgs PoseStamped message to frame target_frame, returns the resulting PoseStamped.
transformQuaternion(target_frame, quat_msg) -> quat_msg
Transforms a geometry_msgs QuaternionStamped message to 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(... etc
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
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.






