Main Content

Get Transform

Get transformation between source and target frame from ROS network

Since R2023b

  • ROS Get Transform Block

Libraries:
ROS Toolbox / ROS

Description

The Get Transform block reads the transformation value between the specified source and target coordinate frames from the ROS network. Use this block when transformations between different frames are published by nodes on the ROS network. On each simulation step, the block checks whether a transformation is available between the specified frames. If it is available, the block outputs the outputs a geometry_msgs/TransformStamped non-virtual bus or a homogeneous transformation matrix as a 4-by-4 double matrix.

You can use the output transformation value to transform the points in source frame to target frame using the pre-multiply convention. The block can access all frames with dynamic transformations under tf topic on the ROS Network.

Ports

Output

expand all

Transformation availability indicator, returned as a logical. If the output is 1, then a transformation exists on the ROS network between the specified source and target frames in last sample hit. This output can be used to trigger subsystems for processing new messages received in the ROS network.

Data Types: Boolean

Homogeneous transformation value between source and target frame, returned as a non-virtual bus or a 4-by-4 double matrix.

Parameters

expand all

Main

Source for specifying frames, specified as one of the following:

  • Select from ROS network — Use Select to select the source and target frames. The Target and Message type parameters are set automatically. You must be connected to a ROS network.

  • Specify your own — Enter the source and target frames manually in Source and Target parameters respectively. You must match the names of the frames exactly.

Target coordinate frame, specified as a string. When Frame source is set to Select from ROS network, use Select to select a frame from the ROS network. You must be connected to a ROS network to get a list of frames available in the network transformation tree. Otherwise, set Frame source to Specify your own and specify the frame you want.

Source coordinate frame, specified as a string. When Frame source is set to Select from ROS network, use Select to select a frame from the ROS network. You must be connected to a ROS network to get a list of frames available in the network transformation tree. Otherwise, set Frame source to Specify your own and specify the frame you want.

Format of the output transformation value, specified as one of these options:

  • busgeometry_msgs/TransformStamped non-virtual bus

  • double4-by-4 double matrix

Interval between outputs, specified as a scalar. In simulation, the sample time follows simulation time and not actual wall-clock time.

This default value indicates that the block sample time is inherited. For more information about the inherited sample time type, see Specify Sample Time (Simulink).

Extended Capabilities

C/C++ Code Generation
Generate C and C++ code using Simulink® Coder™.

Version History

Introduced in R2023b