canTransform

Verify if transformation is available

Description

example

isAvailable = canTransform(tftree,targetframe,sourceframe) verifies if a transformation between the source frame and target frame is available at the current time in tftree. Create the tftree object using rostf, which requires a connection to a ROS network.

isAvailable = canTransform(tftree,targetframe,sourceframe,sourcetime) verifies if a transformation is available for the source time. If sourcetime is outside the buffer window, the function returns false.

example

isAvailable = canTransform(bagSel,targetframe,sourceframe) verifies if a transformation is available in a rosbag in bagSel. To get the bagSel input, load a rosbag using rosbag.

isAvailable = canTransform(bagSel,targetframe,sourceframe,sourcetime) verifies if a transformation is available in a rosbag for the source time. If sourcetime is outside the buffer window, the function returns false.

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.

ipaddress = '192.168.17.129';
rosinit(ipaddress,11311)
Initializing global node /matlab_global_node_33798 with NodeURI http://192.168.17.1:56771/
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.Z = 0.75;

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_33798 with NodeURI http://192.168.17.1:56771/

This example shows how to set up a ROS transformation tree and transform frames based on transformation tree information. It uses time-buffered transformations to access transformations at different times.

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

ipaddress = '192.168.17.129';
rosinit(ipaddress,11311)
Initializing global node /matlab_global_node_14346 with NodeURI http://192.168.17.1:56312/
tftree = rostf;
pause(1)

Look at the available frames on the transformation tree.

tftree.AvailableFrames
ans = 36×1 cell
    {'base_footprint'            }
    {'base_link'                 }
    {'camera_depth_frame'        }
    {'camera_depth_optical_frame'}
    {'camera_link'               }
    {'camera_rgb_frame'          }
    {'camera_rgb_optical_frame'  }
    {'caster_back_link'          }
    {'caster_front_link'         }
    {'cliff_sensor_front_link'   }
    {'cliff_sensor_left_link'    }
    {'cliff_sensor_right_link'   }
    {'gyro_link'                 }
    {'mount_asus_xtion_pro_link' }
    {'odom'                      }
    {'plate_bottom_link'         }
    {'plate_middle_link'         }
    {'plate_top_link'            }
    {'pole_bottom_0_link'        }
    {'pole_bottom_1_link'        }
    {'pole_bottom_2_link'        }
    {'pole_bottom_3_link'        }
    {'pole_bottom_4_link'        }
    {'pole_bottom_5_link'        }
    {'pole_kinect_0_link'        }
    {'pole_kinect_1_link'        }
    {'pole_middle_0_link'        }
    {'pole_middle_1_link'        }
    {'pole_middle_2_link'        }
    {'pole_middle_3_link'        }
      ⋮

Check if the desired transformation is now available. For this example, check for the transformation from 'camera_link' to 'base_link'.

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

Get the transformation for 3 seconds from now. The getTransform function will wait until the transformation becomes available with the specified timeout.

desiredTime = rostime('now') + 3;
tform = getTransform(tftree,'base_link','camera_link',...
                     desiredTime,'Timeout',5);

Create a ROS message to transform. Messages can also be retrieved 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;

Transform the ROS message to the 'base_link' frame using the desired time previously saved.

tfpt = transform(tftree,'base_link',pt,desiredTime);

Optional: You can also use apply with the stored tform to apply this transformation to the pt message.

tfpt2 = apply(tform,pt);

Shut down the ROS network.

rosshutdown
Shutting down global node /matlab_global_node_14346 with NodeURI http://192.168.17.1:56312/

Get transformations from rosbag (.bag) files by loading the rosbag and checking the available frames. From these frames, use getTransform to query the transformation between two coordinate frames.

Load the rosbag.

bag = rosbag('ros_turtlesim.bag');

Get a list of available frames.

frames = bag.AvailableFrames;

Get the latest transformation between two coordinate frames.

tf = getTransform(bag,'world',frames{1});

Check for a transformation available at a specific time and retrieve the transformation. Use canTransform to check if the transformation is available. Specify the time using rostime.

tfTime = rostime(bag.StartTime + 1);
if (canTransform(bag,'world',frames{1},tfTime))
    tf2 = getTransform(bag,'world',frames{1},tfTime);
end

Input Arguments

collapse all

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

Selection of rosbag messages, specified as a BagSelection object handle. To create a selection of rosbag messages, use rosbag.

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

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

ROS or system time, specified as a scalar or Time object handle. The scalar input is converted to a Time object using rostime.

Output Arguments

collapse all

Indicator if transform exists, returned as a boolean. The function returns false if:

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

  • sourcetime is outside the time of the bagSel object.

  • sourcetime is in the future.

  • The transformation is not published yet.

Introduced in R2019b