sendTransform
Send transformation to ROS network
Syntax
Description
Examples
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
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
Usage notes and limitations:
Supported only for the Build Type,
Executable.Usage in MATLAB Function block is not supported.
Version History
Introduced in R2019b
See Also
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.
Sélectionner un site web
Choisissez un site web pour accéder au contenu traduit dans votre langue (lorsqu'il est disponible) et voir les événements et les offres locales. D’après votre position, nous vous recommandons de sélectionner la région suivante : .
Vous pouvez également sélectionner un site web dans la liste suivante :
Comment optimiser les performances du site
Pour optimiser les performances du site, sélectionnez la région Chine (en chinois ou en anglais). Les sites de MathWorks pour les autres pays ne sont pas optimisés pour les visites provenant de votre région.
Amériques
- 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)