Main Content

apply

Transform message entities into target frame

Since R2019b

Description

example

tfentity = apply(tfmsg,entity) applies the transformation represented by the 'TransformStamped' ROS message to the input message object entity.

This function determines the message type of entity and apples the appropriate transformation method to it. If the object cannot handle a particular message type, then MATLAB® displays an error message.

If you want to use only the most current transformation, call transform instead. If you want to store a transformation message for later use, call getTransform, and then call apply.

Note

apply will be removed. Use rosApplyTransform instead. For more information, see ROS Message Structure Functions

Examples

collapse all

Connect to a ROS network to get a TransformStamped ROS message. Specify the IP address to connect. Create a transformation tree and get the transformation between desired frames.

rosinit('192.168.17.129')
Initializing global node /matlab_global_node_73610 with NodeURI http://192.168.17.1:55060/
tftree = rostf;
pause(1);
tform = getTransform(tftree,'base_link','camera_link',...
                     rostime('now'),'Timeout',5);

Create a ROS Point message and apply the transformation. You could also get point messages off the ROS network.

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

tfpt = apply(tform,pt);

Shut down ROS network.

rosshutdown
Shutting down global node /matlab_global_node_73610 with NodeURI http://192.168.17.1:55060/

Input Arguments

collapse all

Transformation message, specified as a TransformStamped ROS message handle. The tfmsg is a ROS message of type: geometry_msgs/TransformStamped.

ROS message, specified as a Message object handle.

Supported messages are:

  • geometry_msgs/PointStamped

  • geometry_msgs/PoseStamped

  • geometry_msgs/PointCloud2

  • geometry_msgs/QuaternionStamped

  • geometry_msgs/Vector3Stamped

Output Arguments

collapse all

Transformed ROS message, returned as a Message object handle.

Version History

Introduced in R2019b

expand all