OccupancyGrid

Create occupancy grid message

Description

The OccupancyGrid object is an implementation of the nav_msgs/OccupancyGrid message type in ROS. The object contains meta-information about the message and the occupancy grid data. To create a binaryOccupancyMap (Robotics System Toolbox) object from a ROS message, use readBinaryOccupancyGrid (Robotics System Toolbox).

Creation

Description

example

msg = rosmessage('nav_msgs/OccupancyGrid'); creates an empty OccupancyGrid object. To specify map information and data, use the map.Info and msg.Data properties. You can also get the occupancy grid messages off the 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.

Information about the map, specified as a MapMetaData object. It contains the width, height, resolution, and origin of the map.

Map data, specified as a vector. The vector is all the occupancy data from each grid location in a single 1-D array.

Object Functions

readBinaryOccupancyGrid (Robotics System Toolbox)Read binary occupancy grid
writeBinaryOccupancyGrid (Robotics System Toolbox)Write values from grid to ROS message

Examples

collapse all

Load two maps, simpleMap and complexMap, as logical matrices. Use whos to display the map.

load exampleMaps.mat
whos *Map*
  Name              Size               Bytes  Class      Attributes

  complexMap       41x52                2132  logical              
  emptyMap         26x27                 702  logical              
  simpleMap        26x27                 702  logical              
  ternaryMap      501x501            2008008  double               

Create a ROS message from simpleMap using a binaryOccupancyMap object. Write the OccupancyGrid message using writeBinaryOccupancyGrid.

bogMap = binaryOccupancyMap(double(simpleMap));
mapMsg = rosmessage('nav_msgs/OccupancyGrid');
writeBinaryOccupancyGrid(mapMsg,bogMap)
mapMsg
mapMsg = 
  ROS OccupancyGrid message with properties:

    MessageType: 'nav_msgs/OccupancyGrid'
         Header: [1x1 Header]
           Info: [1x1 MapMetaData]
           Data: [702x1 int8]

  Use showdetails to show the contents of the message

Use readBinaryOccupancyGrid to convert the ROS message to a binaryOccupancyMap object. Use the object function show to display the map.

bogMap2 = readBinaryOccupancyGrid(mapMsg);
show(bogMap2);

See Also

| | (Robotics System Toolbox) | (Robotics System Toolbox) | (Robotics System Toolbox)

Topics

Introduced in R2019b