readScanAngles

Return scan angles for laser scan range readings

Description

example

angles = readScanAngles(scan) calculates the scan angles, angles, corresponding to the range readings in the laser scan message, scan. 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.

Examples

collapse all

Load sample ROS messages including a ROS laser scan message, scan.

exampleHelperROSLoadMessages

Read the scan angles from the laser scan.

angles = readScanAngles(scan)
angles = 640×1

   -0.5467
   -0.5450
   -0.5433
   -0.5416
   -0.5399
   -0.5382
   -0.5364
   -0.5347
   -0.5330
   -0.5313
      ⋮

Input Arguments

collapse all

'sensor_msgs/LaserScan' ROS message, specified as a LaserScan object handle.

Output Arguments

collapse all

Scan angles for laser scan data, returned as an n-by-1 matrix in radians. Angles are measured counter-clockwise 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.

Introduced in R2019b