Main Content

LaserScan

(To be removed) Create laser scan message

Since R2019b

LaserScan object will be removed in a future release. Use message structure format when you create ROS messages using the rosmessage function, by specifying the Dataformat name-value argument as "struct". You can use rosReadLidarScan, rosReadCartesian, and rosReadScanAngles functions to read laser scan data from ROS messages. For more information, see ROS Message Structure Functions.

Description

The LaserScan object is an implementation of the sensor_msgs/LaserScan message type in ROS. The object contains meta-information about the message and the laser scan data. You can extract the ranges and angles using the Ranges property and the readScanAngles function. To access points in Cartesian coordinates, use readCartesian.

You can also convert this object to a lidarScan (Navigation Toolbox) object to use with other robotics algorithms such as matchScans (Navigation Toolbox), controllerVFH (Navigation Toolbox), or monteCarloLocalization (Navigation Toolbox).

Creation

Description

example

scan = rosmessage('sensor_msgs/LaserScan') creates an empty LaserScan object. You can specify scan info and data using the properties, or you can get these messages off a ROS network using rossubscriber.

Properties

expand all

This property is read-only.

Message type of ROS message, returned as a character vector.

Data Types: char

This property is read-only.

ROS Header message, returned as a Header object. This header message contains the MessageType, sequence (Seq), timestamp (Stamp), and FrameId. Timestamp relates to the acquisition time of the first ray in the scan.

Minimum angle of range data, specified as a scalar in radians. Positive angles are measured from the forward direction of the robot.

Maximum angle of range data, specified as a scalar in radians. Positive angles are measured from the forward direction of the robot.

Angle increment of range data, specified as a scalar in radians.

Time between individual range data points in seconds, specified as a scalar.

Time to complete a full scan in seconds, specified as a scalar.

Minimum valid range value, specified as a scalar.

Maximum valid range value, specified as a scalar.

Range readings from laser scan, specified as a vector. To get the corresponding angles, use readScanAngles.

Intensity values from range readings, specified as a vector. If no valid intensity readings are found, this property is empty.

Object Functions

lidarScan (Navigation Toolbox)Create object for storing 2-D lidar scan
plotDisplay laser or lidar scan readings
readCartesian(To be removed) Read laser scan ranges in Cartesian coordinates
readScanAngles(To be removed) Return scan angles for laser scan range readings

Examples

collapse all

Load, inspect, and display a sample laser scan message.

Create sample messages and inspect the laser scan message data.The scan object is a sample ROS LaserScan message object.

exampleHelperROSLoadMessages
scan
scan = 
  ROS LaserScan message with properties:

       MessageType: 'sensor_msgs/LaserScan'
            Header: [1x1 Header]
          AngleMin: -0.5467
          AngleMax: 0.5467
    AngleIncrement: 0.0017
     TimeIncrement: 0
          ScanTime: 0.0330
          RangeMin: 0.4500
          RangeMax: 10
            Ranges: [640x1 single]
       Intensities: [0x1 single]

  Use showdetails to show the contents of the message

Get ranges and angles from the object properties. Check that the ranges and angles are the same size.

ranges = scan.Ranges;
angles = scan.readScanAngles;
size(ranges)
ans = 1×2

   640     1

size(angles)
ans = 1×2

   640     1

plot(scan)

scan = rosmessage('sensor_msgs/LaserScan')
scan = 
  ROS LaserScan message with properties:

       MessageType: 'sensor_msgs/LaserScan'
            Header: [1x1 Header]
          AngleMin: 0
          AngleMax: 0
    AngleIncrement: 0
     TimeIncrement: 0
          ScanTime: 0
          RangeMin: 0
          RangeMax: 0
            Ranges: [0x1 single]
       Intensities: [0x1 single]

  Use showdetails to show the contents of the message

Version History

Introduced in R2019b

collapse all

R2021a: ROS Message Structure Functions

You can now create messages as structures with fields matching the message object properties. Using structures typically improves performance of creating, updating, and using ROS messages, but message fields are no longer validated when set. Message types and corresponding field values from the structures are validated when sent across the network.

To support message structures as inputs, new functions that operate on specialized ROS messages have been provided. These new functions are based on the existing object functions of message objects, but support ROS and ROS 2 message structures as inputs instead of message objects.

The object functions will be removed in a future release.

Message TypesObject Function NameNew Function Name

Image

CompressedImage

readImage

writeImage

rosReadImage

rosWriteImage

LaserScan

readCartesian

readScanAngles

lidarScan

plot

rosReadCartesian

rosReadScanAngles

rosReadLidarScan

rosPlot

PointCloud2

apply

readXYZ

readRGB

readAllFieldNames

readField

scatter3

rosApplyTransform

rosReadXYZ

rosReadRGB

rosReadAllFieldNames

rosReadField

rosPlot

QuaternionreadQuaternion

rosReadQuaternion

OccupancyGrid

readBinaryOccupanyGrid

readOccupancyGrid

writeBinaryOccupanyGrid

writeOccupanyGrid

rosReadOccupancyGrid

rosReadBinaryOccupancyGrid

rosReadOccupancyGrid

rosWriteBinaryOccupancyGrid

rosWriteOccupancyGrid

OctomapreadOccupancyMap3D

rosReadOccupancyMap3D

PointStamped

PoseStamped

QuaternionStamped

Vector3Stamped

TransformStamped

apply

rosApplyTransform

All messagesshowdetails

rosShowDetails