Main Content

sendTransform

Send a transformation to the ROS 2 network

Since R2023a

Description

example

sendTransform(tftree,tf) broadcasts a dynamic or static transformation tf to the ROS 2 network over /tf or /tf_static topic. tf is a scalar message or a message list of type geometry_msgs/TransformStamped.

sendTransform(tftree,tf,UseStatic=false) broadcasts a dynamic transformation to the ROS 2 network over /tf topic.

sendTransform(tftree,tf,UseStatic=true) broadcasts a static transformation to the ROS 2 network over /tf_static topic.

Examples

collapse all

The tf system in ROS 2 keeps track of multiple coordinate frames and maintains the relationship between them in a tree structure. tf is distributed, so that all coordinate frame information is available to every node in the ROS 2 network. MATLAB® enables you to access this transformation tree. This example familiarizes you with accessing the available coordinate frames, retrieving transformations between them, and transform points, vectors, and other entities between any two coordinate frames.

Create a ROS 2 node on domain ID 25.

node = ros2node("/matlabNode",25);

To create a realistic environment for this example, use exampleHelperROS2StartTfPublisher to broadcast several transformations. The transformations represent a camera that is mounted on a robot.

There are three coordinate frames that are defined in this transformation tree:

  • the robot base frame (robot_base)

  • the camera's mounting point (mounting_point)

  • the optical center of the camera (camera_center)

Two transformations are being published:

  • the transformation from the robot base to the camera's mounting point

  • the transformation from the mounting point to the center of the camera

exampleHelperROS2StartTfPublisher

A visual representation of the three coordinate frames looks as follows.

Here, the x, y, and z axes of each frame are represented by red, green, and blue lines respectively. The parent-child relationship between the coordinate frames is shown through a brown arrow pointing from the child to its parent frame.

Create a new transformation tree using ros2tf object. You can use this object to access all available transformations and apply them to different entities.

tftree = ros2tf(node,...
"DynamicBroadcasterQoS", struct('Depth', 50), ...
"DynamicListenerQoS", struct('Reliability','besteffort'), ...
"StaticBroadcasterQoS", struct('Depth',10), ...
"StaticListenerQoS", struct('Durability','volatile'));

Once the object is created, it starts receiving tf transformations and buffers them internally. Keep the tftree variable in the workspace so that it continues to receive data.

Pause for a little bit to make sure that all transformations are received.

pause(2);

You can see the names of all the available coordinate frames by accessing the AvailableFrames property.

tftree.AvailableFrames
ans = 3×1 cell
    {'camera_center' }
    {'mounting_point'}
    {'robot_base'    }

This should show the three coordinate frames that describe the relationship between the camera, its mounting point, and the robot.

Receive Transformations

Now that the transformations are available, you can inspect them. Any transformation is described by a ROS 2 geometry_msgs/TransformStamped message and has a translational and rotational component.

Retrieve the transformation that describes the relationship between the mounting point and the camera center. Use the getTransform function to do that.

mountToCamera = getTransform(tftree, 'mounting_point', 'camera_center');
mountToCameraTranslation = mountToCamera.transform.translation
mountToCameraTranslation = struct with fields:
    MessageType: 'geometry_msgs/Vector3'
              x: 0
              y: 0
              z: 0.5000

quat = mountToCamera.transform.rotation
quat = struct with fields:
    MessageType: 'geometry_msgs/Quaternion'
              x: 0
              y: 0.7071
              z: 0
              w: 0.7071

mountToCameraRotationAngles = rad2deg(quat2eul([quat.w quat.x quat.y quat.z]))
mountToCameraRotationAngles = 1×3

     0    90     0

Relative to the mounting point, the camera center is located 0.5 meters along the z-axis and is rotated by 90 degrees around the y-axis.

To inspect the relationship between the robot base and the camera's mounting point, call getTransform again.

baseToMount = getTransform(tftree, 'robot_base', 'mounting_point');
baseToMountTranslation = baseToMount.transform.translation
baseToMountTranslation = struct with fields:
    MessageType: 'geometry_msgs/Vector3'
              x: 1
              y: 0
              z: 0

baseToMountRotation = baseToMount.transform.rotation
baseToMountRotation = struct with fields:
    MessageType: 'geometry_msgs/Quaternion'
              x: 0
              y: 0
              z: 0
              w: 1

baseToMountRotationRotationAngles = rad2deg(quat2eul([baseToMountRotation.w baseToMountRotation.x baseToMountRotation.y baseToMountRotation.z]));

The mounting point is located at 1 meter along the robot base's x-axis.

Apply Transformations

Assume now that you have a 3D point that is defined in the camera_center coordinate frame and you want to calculate what the point coordinates in the robot_base frame are.

Use the getTransform function to wait until the transformation between the camera_center and robot_base coordinate frames becomes available. This call blocks until the transformation that takes data from camera_center to robot_base is valid and available in the transformation tree.

getTransform(tftree,'robot_base','camera_center','Timeout', Inf);

Now define a point at position [3 1.5 0.2] in the camera center's coordinate frame. You will subsequently transform this point into robot_base coordinates.

pt = ros2message('geometry_msgs/PointStamped');
pt.header.frame_id = 'camera_center';
pt.point.x = 3;
pt.point.y = 1.5;
pt.point.z = 0.2;

You can transform the point coordinates by calling the transform function on the transformation tree object. Specify what the target coordinate frame of this transformation is. In this example, use robot_base.

tfpt = transform(tftree, 'robot_base', pt)
tfpt = struct with fields:
    MessageType: 'geometry_msgs/PointStamped'
         header: [1×1 struct]
          point: [1×1 struct]

Besides PointStamped messages, the transform function allows you to transform other entities like poses (geometry_msgs/PoseStamped), quaternions (geometry_msgs/QuaternionStamped), and point clouds (sensor_msgs/PointCloud2).

If you want to store a transformation, you can retrieve it with the getTransform function.

robotToCamera = getTransform(tftree, 'robot_base', 'camera_center')
robotToCamera = struct with fields:
       MessageType: 'geometry_msgs/TransformStamped'
            header: [1×1 struct]
    child_frame_id: 'camera_center'
         transform: [1×1 struct]

This transformation can be used to transform coordinates in the camera_center frame into coordinates in the robot_base frame.

robotToCamera.transform.translation
ans = struct with fields:
    MessageType: 'geometry_msgs/Vector3'
              x: 1
              y: 0
              z: 0.5000

robotToCamera.transform.rotation
ans = struct with fields:
    MessageType: 'geometry_msgs/Quaternion'
              x: 0
              y: 0.7071
              z: 0
              w: 0.7071

Send Transformations

You can also broadcast a new transformation to the ROS 2 network.

Assume that you have a simple transformation that describes the offset of the wheel coordinate frame relative to the robot_base coordinate frame. The wheel is mounted -0.2 meters along the y-axis and -0.3 along the z-axis. The wheel has a relative rotation of 30 degrees around the y-axis.

Create the corresponding geometry_msgs/TransformStamped message that describes this transformation. The source coordinate frame, wheel, is placed to the child_frame_id property. The target coordinate frame, robot_base, is added to the header.FrameId property.

tfStampedMsg = ros2message('geometry_msgs/TransformStamped');
tfStampedMsg.child_frame_id = 'wheel';
tfStampedMsg.header.frame_id = 'robot_base';

The transformation itself is described in the Transform property. It contains a Translation and a Rotation. Fill in the values that are listed above.

The Rotation is described as a quaternion. To convert the 30 degree rotation around the y-axis to a quaternion, you can use the axang2quat (Navigation Toolbox) function. The y-axis is described by the [0 1 0] vector and 30 degrees can be converted to radians with the deg2rad function.

tfStampedMsg.transform.translation.x = 0;
tfStampedMsg.transform.translation.y = -0.2;
tfStampedMsg.transform.translation.z = -0.3;

quatrot = axang2quat([0 1 0 deg2rad(30)]);
tfStampedMsg.transform.rotation.w = quatrot(1);
tfStampedMsg.transform.rotation.x = quatrot(2);
tfStampedMsg.transform.rotation.y = quatrot(3);
tfStampedMsg.transform.rotation.z = quatrot(4);

Use ros2time to retrieve the current system time and use that to timestamp the transformation. This lets the recipients know at which point in time this transformation was valid.

tfStampedMsg.header.stamp = ros2time(node,'now');

Broadcast this transformation over the ROS 2 network.

sendTransform(tftree, tfStampedMsg)

The new wheel coordinate frame is now also in the list of available coordinate frames.

tftree.AvailableFrames
ans = 4×1 cell
    {'camera_center' }
    {'mounting_point'}
    {'robot_base'    }
    {'wheel'         }

The final visual representation of all four coordinate frames looks as follows.

You can see that the wheel coordinate frame has the translation and rotation that you specified in sending the transformation.

Stop Example Publisher

Stop the example transformation publisher.

exampleHelperROS2StopTfPublisher

Clear the node.

clear('node')

Input Arguments

collapse all

ROS 2 transformation tree, specified as ros2tf object handle. You can create a ROS 2 transformation tree by using the ros2tf object.

Transformation between coordinate frames, returned as a structure that represents geometry_msgs/TransformStamped. Transformations are structured as a 3-D translation (three-element vector) and a 3-D rotation (quaternion).

Static transform broadcaster setting, specified as "true" or "false". It broadcasts a static or dynamic transformation over /tf_static or /tf topic.

Extended Capabilities

Version History

Introduced in R2023a