Main Content

sendTransform

Send transformation to ROS network

Since R2019b

Description

example

sendTransform(tftree,tf) broadcasts a transform or array of transforms, tf, to the ROS network as a TransformationStamped ROS message.

Examples

collapse all

This example shows how to create a transformation and send it over the ROS network.

Create a ROS transformation tree. Use rosinit to connect a ROS network. Replace ipaddress with your ROS network address.

rosinit;
Launching ROS Core...
....Done in 4.1192 seconds.
Initializing ROS master on http://192.168.125.1:56090.
Initializing global node /matlab_global_node_16894 with NodeURI http://HYD-KVENNAPU:63122/
tftree = rostf;
pause(2)

Verify the transformation you want to send over the network does not already exist. The canTransform function returns false if the transformation is not immediately available.

canTransform(tftree,'new_frame','base_link')
ans = logical
   0

Create a TransformStamped message. Populate the message fields with the transformation information.

tform = rosmessage('geometry_msgs/TransformStamped');
tform.ChildFrameId = 'new_frame';
tform.Header.FrameId = 'base_link';
tform.Transform.Translation.X = 0.5;
tform.Transform.Rotation.X = 0.5;
tform.Transform.Rotation.Y = 0.5;
tform.Transform.Rotation.Z = 0.5;
tform.Transform.Rotation.W = 0.5;

Send the transformation over the ROS network.

sendTransform(tftree,tform)

Verify the transformation is now on the ROS network.

canTransform(tftree,'new_frame','base_link')
ans = logical
   1

Shut down the ROS network.

rosshutdown
Shutting down global node /matlab_global_node_16894 with NodeURI http://HYD-KVENNAPU:63122/
Shutting down ROS master on http://192.168.125.1:56090.

Input Arguments

collapse all

ROS transformation tree, specified as a TransformationTree object handle. You can create a transformation tree by calling the rostf function.

Transformations between coordinate frames, returned as a TransformStamped object handle or as an array of object handles. Transformations are structured as a 3-D translation (3-element vector) and a 3-D rotation (quaternion).

Extended Capabilities

Version History

Introduced in R2019b