Main Content

rosReadTransform

Return transformation from ROS or ROS 2 TransformStamped message structure

Since R2023b

Description

example

T = rosReadTransform(tfmsg) returns an SE(3) homogeneous transformation object T based on the input ROS or ROS 2 geometry_msgs/TransformStamped message structure tfmsg. This syntax is equivalent to specifying the name-value argument OutputOption="se3".

tform = rosReadTransform(tfmsg,OutputOption="single") returns a 4-by-4 homogeneous transformation matrix based on the input ROS or ROS 2 geometry_msgs/TransformStamped message structure tfmsg.

[trans,rotm] = rosReadTransform(tfmsg,OutputOption="pair") returns a 3-by-1 translation vector t, and a 3-by-3 rotation matrix r based on the homogeneous transformation in the input ROS or ROS 2 geometry_msgs/TransformStamped message structure tfmsg.

Examples

collapse all

Load ROS 2 point cloud and transformation messages.

load("ros2PtcloudMsgs.mat")

Visualize the point cloud message ptcloudMsg1.

rosPlot(ptcloudMsg1)
xlabel('X')
ylabel('Y')
zlabel('Z')
view([-180 80])

Note that the vertical direction in the point cloud is represented by the y-axis. You can transform the point cloud such that the z-axis represents the vertical direction. To accomplish this transformation, use the geometry_msgs/TransformStamped message, tfMsg, which contains a transform that rotates the points to a target frame that is 90 degrees in the clockwise direction along x-axis. Read the translation and rotation values from tfMsg using the rosReadTransform function.

[trans,rot] = rosReadTransform(tfMsg,OutputOption="pair")
trans = 3×1

     0
     0
     0

rot = 3×3

    1.0000         0         0
         0    0.0000    1.0000
         0   -1.0000    0.0000

Transform the point cloud to the target frame using the rosApplyTransform function.

transformedPtcloudMsg = rosApplyTransform(tfMsg,ptcloudMsg1);

Visualize the transformed point cloud. Note that the vertical direction is now represented by the z-axis.

rosPlot(transformedPtcloudMsg)
view(-180,14)

Input Arguments

collapse all

ROS or ROS 2 transformation message, specified as a geometry_msgs/TransformStamped message structure.

Output Arguments

collapse all

SE(3) homogeneous transformation, returned as an se3 object handle.

Dependencies

Specify no name-value argument or OutputOption="se3" when you call the rosReadTransform function.

Homogeneous transformation, returned as a 4-by-4 numeric matrix.

Specify OutputOption="single" name-value argument when you call the rosReadTransform function.

Amount of translation, returned as a 3-by-1 numeric vector.

Dependencies

Specify OutputOption="pair" name-value argument when you call the rosReadTransform function.

Rotation matrix, returned as a 3-by-3 numeric matrix.

Dependencies

Specify OutputOption="pair" name-value argument when you call the rosReadTransform function.

Extended Capabilities

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

Version History

Introduced in R2023b