Main Content

getTransform

Retrieve transformation between two coordinate frames

Since R2019b

Description

TransformationTree Object

tf = getTransform(tftree,targetframe,sourceframe) returns the latest known transformation between two coordinate frames in tftree. Create the tftree object using rostf, which requires a connection to a ROS network.

Transformations are structured as a 3-D translation (three-element vector) and a 3-D rotation (quaternion).

tf = getTransform(tftree,targetframe,sourceframe,sourcetime) returns the transformation from tftree at the given source time. If the transformation is not available at that time, the function returns an error.

example

tf = getTransform(___,"Timeout",timeout) also specifies a timeout period, in seconds, to wait for the transformation to be available. If the transformation does not become available in the timeout period, the function returns an error. Use this syntax with any of the input arguments in previous syntaxes.

BagSelection Object

example

tf = getTransform(bagSel,targetframe,sourceframe) returns the latest transformation between two frames in the rosbag in bagSel. To get the bagSel input, load a rosbag using rosbag.

tf = getTransform(bagSel,targetframe,sourceframe,sourcetime) returns the transformation at the specified sourcetime in the rosbag in bagSel.

tf = getTransform(___,"DataFormat","struct") returns the ROS geometry_msgs/TransformStamped message in the specified format.

rosbagreader Object

example

tf = getTransform(bagreader,targetframe,sourceframe) returns the latest transformation between two frames in the rosbag in bagreader.

tf = getTransform(bagreader,targetframe,sourceframe,sourcetime) returns the transformation at the specified sourcetime in the rosbag in bagreader.

tf = getTransform(___,"DataFormat","struct") returns the ROS geometry_msgs/TransformStamped message in the specified format.

Examples

collapse all

This example shows how to set up a ROS transformation tree and transform frames based on transformation tree information. It uses time-buffered transformations to access transformations at different times.

Create a ROS transformation tree. Use rosinit to connect to a ROS network. Replace ipaddress with your ROS network address.

ipaddress = '192.168.17.129';
rosinit(ipaddress,11311)
Initializing global node /matlab_global_node_14346 with NodeURI http://192.168.17.1:56312/
tftree = rostf;
pause(1)

Look at the available frames on the transformation tree.

tftree.AvailableFrames
ans = 36×1 cell
    {'base_footprint'            }
    {'base_link'                 }
    {'camera_depth_frame'        }
    {'camera_depth_optical_frame'}
    {'camera_link'               }
    {'camera_rgb_frame'          }
    {'camera_rgb_optical_frame'  }
    {'caster_back_link'          }
    {'caster_front_link'         }
    {'cliff_sensor_front_link'   }
    {'cliff_sensor_left_link'    }
    {'cliff_sensor_right_link'   }
    {'gyro_link'                 }
    {'mount_asus_xtion_pro_link' }
    {'odom'                      }
    {'plate_bottom_link'         }
    {'plate_middle_link'         }
    {'plate_top_link'            }
    {'pole_bottom_0_link'        }
    {'pole_bottom_1_link'        }
    {'pole_bottom_2_link'        }
    {'pole_bottom_3_link'        }
    {'pole_bottom_4_link'        }
    {'pole_bottom_5_link'        }
    {'pole_kinect_0_link'        }
    {'pole_kinect_1_link'        }
    {'pole_middle_0_link'        }
    {'pole_middle_1_link'        }
    {'pole_middle_2_link'        }
    {'pole_middle_3_link'        }
      ⋮

Check if the desired transformation is now available. For this example, check for the transformation from 'camera_link' to 'base_link'.

canTransform(tftree,'base_link','camera_link')
ans = logical
   1

Get the transformation for 3 seconds from now. The getTransform function will wait until the transformation becomes available with the specified timeout.

desiredTime = rostime('now') + 3;
tform = getTransform(tftree,'base_link','camera_link',...
                     desiredTime,'Timeout',5);

Create a ROS message to transform. Messages can also be retrieved off the ROS network.

pt = rosmessage('geometry_msgs/PointStamped');
pt.Header.FrameId = 'camera_link';
pt.Point.X = 3;
pt.Point.Y = 1.5;
pt.Point.Z = 0.2;

Transform the ROS message to the 'base_link' frame using the desired time previously saved.

tfpt = transform(tftree,'base_link',pt,desiredTime);

Optional: You can also use apply with the stored tform to apply this transformation to the pt message.

tfpt2 = apply(tform,pt);

Shut down the ROS network.

rosshutdown
Shutting down global node /matlab_global_node_14346 with NodeURI http://192.168.17.1:56312/

This example shows how to access time-buffered transformations on the ROS network. Access transformations for specific times and modify the BufferTime property based on your desired times.

Create a ROS transformation tree. Use rosinit to connect to a ROS network. Replace ipaddress with your ROS network address.

ipaddress = '192.168.17.129';
rosinit(ipaddress,11311)
Initializing global node /matlab_global_node_78006 with NodeURI http://192.168.17.1:56344/
tftree = rostf;
pause(2);

Get the transformation from 1 second ago.

desiredTime = rostime('now') - 1;
tform = getTransform(tftree,'base_link','camera_link',desiredTime);

The transformation buffer time is 10 seconds by default. Modify the BufferTime property of the transformation tree to increase the buffer time and wait for that buffer to fill.

tftree.BufferTime = 15;
pause(15);

Get the transformation from 12 seconds ago.

desiredTime = rostime('now') - 12;
tform = getTransform(tftree,'base_link','camera_link',desiredTime);

You can also get transformations at a time in the future. The getTransform function will wait until the transformation is available. You can also specify a timeout to error if no transformation is found. This example waits 5 seconds for the transformation at 3 seconds from now to be available.

desiredTime = rostime('now') + 3;
tform = getTransform(tftree,'base_link','camera_link',desiredTime,'Timeout',5);

Shut down the ROS network.

rosshutdown
Shutting down global node /matlab_global_node_78006 with NodeURI http://192.168.17.1:56344/

Get transformations from rosbag (.bag) files by loading the rosbag and checking the available frames. From these frames, use getTransform to query the transformation between two coordinate frames.

Load the rosbag.

bag = rosbag('ros_turtlesim.bag');

Get a list of available frames.

frames = bag.AvailableFrames;

Get the latest transformation between two coordinate frames.

tf = getTransform(bag,'world',frames{1});

Check for a transformation available at a specific time and retrieve the transformation. Use canTransform to check if the transformation is available. Specify the time using rostime.

tfTime = rostime(bag.StartTime + 1);
if (canTransform(bag,'world',frames{1},tfTime))
    tf2 = getTransform(bag,'world',frames{1},tfTime);
end

Get transformations from rosbag (.bag) files by loading the rosbag and checking the available frames. From these frames, use getTransform to query the transformation between two coordinate frames.

Load the rosbag.

bagMsgs = rosbagreader("ros_turtlesim.bag")
bagMsgs = 
  rosbagreader with properties:

           FilePath: '/tmp/Bdoc24a_2528353_1224495/tp3a7068b3/ros-ex81142742/ros_turtlesim.bag'
          StartTime: 1.5040e+09
            EndTime: 1.5040e+09
        NumMessages: 6089
    AvailableTopics: [6x3 table]
    AvailableFrames: {2x1 cell}
        MessageList: [6089x4 table]

Get a list of available frames.

frames = bagMsgs.AvailableFrames
frames = 2x1 cell
    {'turtle1'}
    {'world'  }

Get the latest transformation between two coordinate frames.

tf = getTransform(bagMsgs,'world',frames{1})
tf = 
  ROS TransformStamped message with properties:

     MessageType: 'geometry_msgs/TransformStamped'
          Header: [1x1 Header]
       Transform: [1x1 Transform]
    ChildFrameId: 'turtle1'

  Use showdetails to show the contents of the message

Check for a transformation available at a specific time and retrieve the transformation. Use canTransform to check if the transformation is available. Specify the time using rostime.

tfTime = rostime(bagMsgs.StartTime + 1);
if (canTransform(bagMsgs,'world',frames{1},tfTime))
    tf2 = getTransform(bagMsgs,'world',frames{1},tfTime);
end

Input Arguments

collapse all

ROS transformation tree, specified as a TransformationTree object. You can create a transformation tree by calling the rostf function.

Selection of rosbag messages, specified as a BagSelection object. To create a selection of rosbag messages, use rosbag.

Index of the messages in the rosbag, specified as a rosbagreader object.

Target coordinate frame, specified as a string scalar or character vector. You can view the available frames for transformation by calling tftree.AvailableFrames.

Initial coordinate frame, specified as a string scalar or character vector. You can view the available frames for transformation by calling tftree.AvailableFrames.

ROS or system time, specified as a Time object handle. By default, sourcetime is the ROS simulation time published on the clock topic. If you set the use_sim_time ROS parameter to true, sourcetime returns the system time. You can create a Time object using rostime.

Timeout for receiving the transform, specified as a scalar in seconds. The function returns an error if the timeout is reached and no transform becomes available.

Transformed ROS messages format, returned as message "object" of specific type or message "struct" with compatible fields. Using "struct" can be faster than using message "object".

Output Arguments

collapse all

Transformation between coordinate frames, returned as a TransformStamped object handle. Transformations are structured as a 3-D translation (three-element vector) and a 3-D rotation (quaternion).

Extended Capabilities

Version History

Introduced in R2019b

expand all