Main Content

TransformStamped

Create transformation message

Since R2019b

Description

The TransformStamped object is an implementation of the geometry_msgs/TransformStamped message type in ROS. The object contains meta-information about the message itself and the transformation. The transformation has a translational and rotational component.

Creation

Description

example

tform = getTransform(tftree,targetframe,sourceframe) returns the latest known transformation between two coordinate frames. Transformations are structured as a 3-D translation (3-element vector) and a 3-D rotation (quaternion).

Properties

expand all

This property is read-only.

Message type of ROS message, returned as a character vector.

Data Types: char

This property is read-only.

ROS Header message, returned as a Header object. This header message contains the MessageType, sequence (Seq), timestamp (Stamp), and FrameId.

Second coordinate frame to transform point into, specified as a character vector.

This property is read-only.

Transformation message, specified as a Transform object. The object contains the MessageType with a Translation vector and Rotation quaternion.

Object Functions

applyTransform message entities into target frame

Examples

collapse all

This example looks at the TransformStamped object to show the underlying structure of a TransformStamped ROS message. After setting up a network and transformations, you can create a transformation tree and get transformations between specific coordinate systems. Using showdetails lets you inspect the information in the transformation. It contains the ChildFrameId, Header, and Transform.

Start ROS network and setup transformations.

rosinit
Launching ROS Core...
.Done in 2.0279 seconds.
Initializing ROS master on http://172.30.252.152:51942.
Initializing global node /matlab_global_node_14076 with NodeURI http://dcc163793glnxa64:40717/ and MasterURI http://localhost:51942.
exampleHelperROSStartTfPublisher

Create transformation tree and wait for tree to update. Get the transform between the robot base and its camera center.

tftree = rostf;
waitForTransform(tftree,'camera_center','robot_base');
tform = getTransform(tftree,'camera_center','robot_base');

Inspect the TransformStamped object.

showdetails(tform)
  Header          
    Stamp      
      Sec  :  1707799425
      Nsec :  173787688
    Seq     :  0
    FrameId :  camera_center
  Transform       
    Translation    
      X :  0.5
      Y :  0
      Z :  -1
    Rotation       
      X :  0
      Y :  -0.7071067811865476
      Z :  0
      W :  0.7071067811865476
  ChildFrameId :  robot_base

Access the Translation vector inside the Transform property.

trans = tform.Transform.Translation
trans = 
  ROS Vector3 message with properties:

    MessageType: 'geometry_msgs/Vector3'
              X: 0.5000
              Y: 0
              Z: -1.0000

  Use showdetails to show the contents of the message

Stop the example transformation publisher.

exampleHelperROSStopTfPublisher

Shutdown ROS network.

rosshutdown
Shutting down global node /matlab_global_node_14076 with NodeURI http://dcc163793glnxa64:40717/ and MasterURI http://localhost:51942.
Shutting down ROS master on http://172.30.252.152:51942.

Apply a transformation from a TransformStamped object to a PointStamped message.

Start ROS network and setup transformations.

rosinit
Launching ROS Core...
Done in 0.84601 seconds.
Initializing ROS master on http://172.30.250.147:49234.
Initializing global node /matlab_global_node_07929 with NodeURI http://dcc277159glnxa64:42507/ and MasterURI http://localhost:49234.
exampleHelperROSStartTfPublisher

Create transformation tree and wait for tree to update. Get the transform between the robot base and its camera center. Inspect the transformation.

tftree = rostf;
waitForTransform(tftree,'camera_center','robot_base');
tform = getTransform(tftree,'camera_center','robot_base');
showdetails(tform)
  Header          
    Stamp      
      Sec  :  1707798986
      Nsec :  142561333
    Seq     :  0
    FrameId :  camera_center
  Transform       
    Translation    
      X :  0.5
      Y :  0
      Z :  -1
    Rotation       
      X :  0
      Y :  -0.7071067811865476
      Z :  0
      W :  0.7071067811865476
  ChildFrameId :  robot_base

Create point to transform. You could also get this point message off the ROS network.

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

Apply the transformation to the point.

tfpt = apply(tform,pt);

Shutdown ROS network.

rosshutdown
Shutting down global node /matlab_global_node_07929 with NodeURI http://dcc277159glnxa64:42507/ and MasterURI http://localhost:49234.
Shutting down ROS master on http://172.30.250.147:49234.

Version History

Introduced in R2019b