Main Content

rosReadBinaryOccupancyGrid

Read binary occupancy grid data from ROS or ROS 2 message structure

Since R2021a

Description

map = rosReadBinaryOccupancyGrid(msg) returns a binaryOccupancyGrid object by reading the data inside a ROS or ROS 2 message structure, msg, which must be a 'nav_msgs/OccupancyGrid' message. All message data values greater than or equal to the occupancy threshold are set to occupied, 1, in the map. All other values, including unknown values (-1) are set to unoccupied, 0, in the map.

map = rosReadBinaryOccupancyGrid(msg,thresh) specifies a threshold, thresh, for occupied values. All values greater than or equal to the threshold are set to occupied, 1. All other values are set to unoccupied, 0.

map = rosReadBinaryOccupancyGrid(msg,thresh,val) specifies a value to set for unknown values (-1 ). By default, all unknown values are set to unoccupied, 0.

Input Arguments

collapse all

ROS or ROS 2 'nav_msgs/OccupancyGrid' message, specified as a message structure.

Threshold for occupied values, specified as a scalar. Any value greater than or equal to the threshold is set to occupied, 1. All other values are set to unoccupied, 0.

Data Types: double

Value to replace unknown values, specified as either 0 or 1. Unknown message values (-1) are set to the given value.

Data Types: double | logical

Output Arguments

collapse all

Binary occupancy grid, returned as a binaryOccupancyMap object handle. map contains the occupancy data from a 'nav_msgs/OccupancyGrid' message converted to binary values. The object stores a grid of binary values, where 1 indicates an occupied location and 0 indications an unoccupied location.

Extended Capabilities

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

Version History

Introduced in R2021a