Main Content

canTransform

Verify if transformation is available

Since R2023b

Description

example

isAvailable = canTransform(bagReader,targetframe,sourceframe) verifies if a transformation that takes coordinates in the sourceframe into the corresponding coordinates in the targetframe is available. isAvailable is true if that transformation is available and false if that transformation is not available. Use getTransform to retrieve the transformation.

isAvailable = canTransform(bagReader,targetframe,sourceframe,sourcetime) verifies that the transformation is available for the time sourcetime. If sourcetime is outside of the buffer window for the transformation, the function returns false. Use getTransform with the sourcetime argument to retrieve the transformation.

Examples

collapse all

Specify the full path to the log folder.

folderPath = fullfile(pwd,"tf_and_static_bag");

Create a ros2bagreader object that contains all the messages in the log file.

bagReader = ros2bagreader(folderPath);
pause(1)

Use the AvailableFrames property to see the all the available transformation frames.

frames = bagReader.AvailableFrames
frames = 8×1 cell
    {'frame1'}
    {'frame2'}
    {'frame3'}
    {'frame4'}
    {'frame5'}
    {'frame6'}
    {'frame7'}
    {'frame8'}

Use getTransform to access the latest transformation between the first and second coordinate frames.

tf2Msg = getTransform(bagReader,frames{2},frames{1})
tf2Msg = struct with fields:
       MessageType: 'geometry_msgs/TransformStamped'
            header: [1×1 struct]
    child_frame_id: 'frame1'
         transform: [1×1 struct]

Use canTransform to determine whether the transformation is available at a specific time by using ros2time. Use StartTime property to access the latest transformation between the first and second coordinate frames at that specific time.

tf2Time = ros2time(bagReader.StartTime+1);
isAvailable = canTransform(bagReader,frames{2},frames{1},tf2Time);
if isAvailable
    tf2MsgAtTime = getTransform(bagMsgs,frames{2},frames{1},tf2Time);
end

Input Arguments

collapse all

Index of messages in a ROS 2 bag object, specified as a ros2bagreader object handle.

Target coordinate frame, specified as a string scalar or character vector. You can view the available frames for transformation by calling bagReader.AvailableFrames.

Data Types: char | string

Initial coordinate frame, specified as a string scalar or character vector. You can view the available frames for transformation using bagReader.AvailableFrames.

Data Types: char | string

ROS 2 or system time, specified as a scalar or structure that resembles the output of ros2time function. The software converts the scalar input into structure using ros2time. By default, sourcetime corresponds to the system time. If you set the use_sim_time ROS 2 parameter to 1 (true) on the ros2node object associated with the ros2time function, sourcetime corresponds to the ROS 2 simulation time published on the /clock topic.

Data Types: struct | double

Output Arguments

collapse all

Transformation verification entity, returned as 1 (true) or 0 (false). The functions returns 1 (true) if a transformation is available between sourceframe and targetframe.

The function returns 0 (false) if any of these conditions is true:

  • sourcetime is outside the buffer window for a bagreader object.

  • sourcetime is in the future.

  • The transformation is not published yet.

Version History

Introduced in R2023b