Main Content

ros2tf

Receive, send, verify and apply ROS 2 transformations

Since R2023a

Description

Use ros2tf to create a ROS 2 transformation tree, which allows you to access the dynamic transformations tf and static transformations tf_static, that are shared over the ROS 2 network. You can receive transformations and apply them to different entities. You can also send transformations and share them with the rest of the ROS 2 network.

  1. Dynamic transform broadcasts the transformation message over coordinate frames that change relative to each other through time. These apply to the moving parts of the robot.

  2. Static transform broadcasts the transformation message over fixed coordinate frames. These apply to the non moving parts of the robot.

ROS 2 uses the tf2_ros transformation library to keep track of the relationship between multiple coordinate frames. The relative transformations between these coordinate frames are maintained in a tree structure. You can transform entities like poses and points between any two coordinate frames by querying this tree.

The transformation tree changes over time and by default, the transformations are buffered for up to 10 seconds. You can access transformations at any time in this buffer window and the result will be interpolated to the exact time that you specify.

Creation

Description

example

tftree = ros2tf(node) creates a ROS transformation tree object handle that the transformation tree is attached to. The node is the node connected to the ROS 2 network that publishes transformations.

tftree = ros2tf(node,'DynamicBroadcasterQoS',struct('Depth',200,'Reliability','besteffort')) declares quality of service settings for the dynamic transform broadcaster while creating transformation tree.

tftree = ros2tf(node,'StaticBroadcasterQoS',struct('Depth',50)) declares quality of service settings for the static transform broadcaster while creating transformation tree.

tftree = ros2tf(node',DynamicListenerQoS',struct('Depth',200,'Reliability','besteffort')) declares quality of service settings for the dynamic transform listener while creating transformation tree.

tftree = ros2tf(node,'StaticListenerQoS',struct('Depth',50)) declares quality of service settings for the static transform listener while creating transformation tree.

Properties

expand all

This property is read-only.

List of all available coordinate frames, specified as a cell array. This list of available frames updates if new transformations are received by the transformation tree object. It is empty if no frames are in the tree.

Example: {'camera_center';'mounting_point';'robot_base'}

Data Types: cell

This property is read-only.

Time when the last transformation was received, specified as a structure that resembles ros2time. It is empty if no transformation is received.

Data Types: struct

Length of time transformations are buffered, specified as a scalar in seconds. If you change the buffer time from the current value, the transformation tree and all transformations are reinitialized. You must wait for the entire buffer time to be completed to get a fully buffered transformation tree.

This property is read-only.

Quality of service settings to be declared for the dynamic transform broadcaster while creating transformation tree, specified as "struct". Specify a structure containing one or more of these QoS settings:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Liveliness

  • Lease Duration

These QoS settings are used by the TransformBroadCaster of tf2_ros, while broadcasting tf2_msgs/TFMessage onto /tf topic.

Example: {'History: keeplast, Depth: 100, Reliability: reliable, Durability: volatile'}

Data Types: struct

This property is read-only.

Quality of service settings to be declared for the static transform broadcaster while creating transformation tree, specified as "struct". Specify a structure containing one or more of these QoS settings:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Liveliness

  • Lease Duration

These QoS settings are used by the StaticTransformBroadCaster of tf2_ros, while broadcasting tf2_msgs/TFMessage onto /tf_static topic.

Example: {'History: keeplast, Depth: 1, Reliability: reliable, Durability: transientlocal'}

Data Types: struct

This property is read-only.

Quality of service settings to be declared for the dynamic transform listener while creating transformation tree, specified as "struct". Specify a structure containing one or more of these QoS settings:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Liveliness

  • Lease Duration

These QoS settings are used by the TransformListener of tf2_ros, while listening to tf2_msgs/TFMessage onto /tf topic.

Example: {'History: keeplast, Depth: 100, Reliability: reliable, Durability: volatile'}

Data Types: struct

This property is read-only.

Quality of service settings to be declared for the Static transform listener while creating transformation tree, specified as "struct". Specify a structure containing one or more of these QoS settings:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Liveliness

  • Lease Duration

These QoS settings are used by the StaticTransformListener of tf2_ros, while listening to tf2_msgs/TFMessage onto /tf_static topic.

Example: {'History: keeplast, Depth: 100, Reliability: reliable, Durability: transientlocal'}

Data Types: struct

Object Functions

getTransformReturn the transformation between two coordinate frames
transformTransform message entities into target coordinate frame
sendTransformSend a transformation to the ROS 2 network
canTransformVerify if transformation is available

Examples

collapse all

This example assumes that a ROS 2 node publishes transformations between robot_base and camera_center. For example, a real or simulated TurtleBot would do that.

Create a ROS 2 node on domain ID 25. Use the example helper function to publish transformation data.

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

Retrieve the transformation tree object.

tftree = ros2tf(node);
pause(1)

Use the AvailableFrames property to see the transformation frames available. These transformations were specified separately prior to connecting to the network.

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

Use the LastUpdateTime property to see the time when the last transformation was received.

updateTime = tftree.LastUpdateTime
updateTime = struct with fields:
    MessageType: 'builtin_interfaces/Time'
            sec: 1670925404
        nanosec: 440832800

Wait for the transformation that takes data from camera_center to robot_base. It waits for the transformation to be valid within 5 seconds.

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

Define a point [3 1.5 0.2] in the camera's coordinate frame.

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;

The transformation is now available, so transform the point into the robot_base frame.

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

Display the transformed point coordinates.

tfpt.point
ans = struct with fields:
    MessageType: 'geometry_msgs/Point'
              x: 1.2000
              y: 1.5000
              z: -2.5000

Stop the example transformation publisher.

exampleHelperROS2StopTfPublisher

Clear the node.

clear('node')

Extended Capabilities

Version History

Introduced in R2023a