TransformStamped
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
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).tform
= getTransform(tftree
,targetframe
,sourceframe
)
Properties
MessageType
— Message type of ROS message
character vector
This property is read-only.
Message type of ROS message, returned as a character vector.
Data Types: char
Header
— ROS Header message
Header
object
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
.
ChildFrameID
— Second coordinate frame to transform point into
character vector
Second coordinate frame to transform point into, specified as a character vector.
Transform
— Transformation message
Transform
object
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
apply | Transform message entities into target frame |
Examples
Inspect Sample TransformStamped
Object
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 0.45256 seconds. Initializing ROS master on http://172.29.220.45:59109. Initializing global node /matlab_global_node_22994 with NodeURI http://dcc830977glnxa64:38495/ and MasterURI http://localhost:59109.
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 : 1692472189 Nsec : 978014736 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_22994 with NodeURI http://dcc830977glnxa64:38495/ and MasterURI http://localhost:59109. Shutting down ROS master on http://172.29.220.45:59109.
Apply Transformation using TransformStamped
Object
Apply a transformation from a TransformStamped
object to a PointStamped
message.
Start ROS network and setup transformations.
rosinit
Launching ROS Core... Done in 0.38904 seconds. Initializing ROS master on http://172.29.196.158:49898. Initializing global node /matlab_global_node_93796 with NodeURI http://dcc427349glnxa64:45523/ and MasterURI http://localhost:49898.
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 : 1692471998 Nsec : 121009036 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_93796 with NodeURI http://dcc427349glnxa64:45523/ and MasterURI http://localhost:49898. Shutting down ROS master on http://172.29.196.158:49898.
Version History
Introduced in R2019b
Open Example
You have a modified version of this example. Do you want to open this example with your edits?
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list:
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)