Main Content

Read A ROS Scan Message In Simulink®

This example shows how to read in a laser scan message from a ROS network. Calculate the points in Cartesian coordinates and visualize with a 2D plot.

Start a ROS network.

rosinit
Launching ROS Core...
.Done in 1.3108 seconds.
Initializing ROS master on http://172.29.210.99:49600.
Initializing global node /matlab_global_node_62687 with NodeURI http://dcc451503glnxa64:42695/ and MasterURI http://localhost:49600.

Load a sample ROS LaserScan message. Create a publisher for the topic /scan and specify the message type as sensor_msgs/LaserScan. Publish the sample LaserScan message on this topic.

exampleHelperROSLoadScan
pub = rospublisher("/scan","sensor_msgs/LaserScan",DataFormat="struct");
send(pub,scan)

Open the Simulink® model for subscribing to a published message and reading the scan message from ROS.

open_system("read_scan_example_model.slx")

Ensure that the Subscribe block is subscribing to the /scan topic.

The model reads the LaserScan message from the ROS network. The Read Scan block extracts range and angle data from the message. These are then fed to the plotXY MATLAB Function block which converts the ranges and angles to points in Cartesian coordinates and visualizes them on a plot. All NaN values are ignored.

Run the model. The plot shows the points in the laser scan.

Shut down the ROS network.

rosshutdown
Shutting down global node /matlab_global_node_62687 with NodeURI http://dcc451503glnxa64:42695/ and MasterURI http://localhost:49600.
Shutting down ROS master on http://172.29.210.99:49600.