Main Content

rosReadCartesian

Read laser scan ranges in Cartesian coordinates from ROS or ROS 2 message structure

Since R2021a

Description

cart = rosReadCartesian(scan) converts the polar measurements of the ROS or ROS 2 laser scan message structure, scan, into Cartesian coordinates, cart. This function uses the metadata in the message, such as angular resolution and opening angle of the laser scanner, to perform the conversion. Invalid range readings, usually represented as NaN, are ignored in this conversion.

cart = rosReadCartesian(___,Name,Value) provides additional options specified by one or more Name,Value pair arguments. You can specify several name-value pair arguments in any order as Name1,Value1,...,NameN,ValueN.

[cart,angles] = rosReadCartesian(___) returns the scan angles, angles, that are associated with each Cartesian coordinate. Angles are measured counterclockwise around the positive z-axis, with the zero angle along the x-axis. The angles is returned in radians and wrapped to the [ –pi, pi] interval.

Input Arguments

collapse all

ROS or ROS 2 laser scan message of type 'sensor_msgs/LaserScan', specified as a message structure.

Name-Value Arguments

Specify optional pairs of arguments as Name1=Value1,...,NameN=ValueN, where Name is the argument name and Value is the corresponding value. Name-value arguments must appear after other arguments, but the order of the pairs does not matter.

Before R2021a, use commas to separate each name and value, and enclose Name in quotes.

Example: 'RangeLimits',[0.05 2] sets the range limits for the scan in meters

Minimum and maximum range for a scan in meters, specified as a 2-element [min max] vector. All ranges smaller than min or larger than max are ignored during the conversion to Cartesian coordinates.

Output Arguments

collapse all

Cartesian coordinates of laser scan, returned as an n-by-2 matrix in meters.

Scan angles for laser scan data, returned as an n-by-1 matrix in radians. Angles are measured counterclockwise around the positive z-axis, with the zero angle along the x-axis. The angles is returned in radians and wrapped to the [ –pi, pi] interval.

Extended Capabilities

C/C++ Code Generation
Generate C and C++ code using MATLAB® Coder™.

Version History

Introduced in R2021a