getTransform
Retrieve transformation between two coordinate frames
Syntax
Description
TransformationTree
Object
returns the latest known transformation between two coordinate frames in
tf
= getTransform(tftree
,targetframe
,sourceframe
)tftree
. Create the tftree
object
using rostf
, which requires a
connection to a ROS network.
Transformations are structured as a 3-D translation (three-element vector) and a 3-D rotation (quaternion).
returns the transformation from tf
= getTransform(tftree
,targetframe
,sourceframe
,sourcetime
)tftree
at the given source
time. If the transformation is not available at that time, the function returns
an error.
also specifies a timeout period, in seconds, to wait for the transformation to
be available. If the transformation does not become available in the timeout
period, the function returns an error. Use this syntax with any of the input
arguments in previous syntaxes.tf
= getTransform(___,"Timeout",timeout
)
BagSelection
Object
returns the latest transformation between two frames in the rosbag in
tf
= getTransform(bagSel
,targetframe
,sourceframe
)bagSel
. To get the bagSel
input,
load a rosbag using rosbag
.
returns the transformation at the specified tf
= getTransform(bagSel
,targetframe
,sourceframe
,sourcetime
)sourcetime
in
the rosbag in bagSel
.
returns the ROS tf
= getTransform(___,"DataFormat"
,"struct")geometry_msgs/TransformStamped
message in the
specified format.
rosbagreader
Object
returns the latest transformation between two frames in the rosbag in
tf
= getTransform(bagreader
,targetframe
,sourceframe
)bagreader
.
returns the transformation at the specified tf
= getTransform(bagreader
,targetframe
,sourceframe
,sourcetime
)sourcetime
in
the rosbag in bagreader
.
returns the ROS tf
= getTransform(___,"DataFormat"
,"struct")geometry_msgs/TransformStamped
message in the
specified format.
Examples
Input Arguments
Output Arguments
Extended Capabilities
Version History
Introduced in R2019bSee Also
transform
| waitForTransform
| rostf
| canTransform
| rosbag
| rosbagreader