メインコンテンツ

Get Transform

Get transformation between source and target frame from ROS 2 network

Since R2023b

  • ROS 2 Get Transform Icon

Libraries:
ROS Toolbox / ROS 2

Description

The Get Transform block reads the transformation value between the specified source and target coordinate frames from the ROS 2 network. Use this block when transformations between different frames are published by nodes on the ROS 2 network. On each simulation step, the block checks whether a transformation is available between the specified frames. If it is available, the block 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 and listen to all frames with dynamic transformations under tf topic as well as static transformations under tf_static topic on the ROS 2 Network. You can also set separate quality of service (QoS) parameters for the block when it acts as a static and dynamic transformation listener.

Examples

Ports

Output

expand all

Transformation availability indicator, returned as a logical. If the output is 1, then a transformation exists on the ROS 2 network between the specified source and target frames in last sample hit. This output can be used to trigger subsystems for processing new transforms received in the ROS 2 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 Parameters

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

  • Select from ROS 2 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 2 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 2 network, use Select to select a frame from the ROS 2 network. You must be connected to a ROS 2 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 2 network, use Select to select a frame from the ROS 2 network. You must be connected to a ROS 2 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).

Quality of Service (QoS) Parameters for Dynamic Listener and Static Listener

Determines the mode of storing transforms in the queue. The queued transforms will be sent to late-joining listeners. If the queue fills with transforms waiting to be processed, then old transforms will be dropped to make room for new. When set to Keep last, the queue stores the number of transforms set by the Depth property. Otherwise, when set to Keep all, the queue stores all transforms up to the MATLAB® resource limits.

Number of transforms stored in the transform queue when History is set to Keep last.

Affects the guarantee of transform delivery. If Reliable, then delivery is guaranteed, but may retry multiple times. If Best effort, then attempt delivery and do not retry.

Affects persistence of transforms in tf or tf_static topic publishers, which allows late-joining listeners to receive the number of old transforms specified by Depth. If Volatile, then transforms do not persist. If Transient local, then publisher will retain the most recent transforms.

Maximum amount of time allowed between successive transforms, specified as a positive scalar. For dynamic listener QoS setting, this deadline parameter specifies the maximum allowed interval between successive transforms on the tf topic, whereas for static listener QoS setting, it specifies the same for the tf_static topic.

Length of time a transform is considered valid, specified as a positive scalar. The block does not process service requests persisting longer than the specified lifespan in the queue.

For dynamic listener QoS setting, this lifespan parameter specifies the length of time a transform is considered valid on the tf topic, whereas for static listener QoS setting, it specifies the same for the tf_static topic.

Level of liveliness reporting provided by the block acting as a dynamic or a static listener, specified as automatic.

If automatic, the ROS 2 network considers the block to be alive for another Lease Duration after it has received a new transformation message.

Maximum amount of time before which the block has to assert liveliness as a static or dynamic listener, specified as a positive scalar.

Extended Capabilities

expand all

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

Version History

Introduced in R2023b