diff --git a/nav_msgs/msg/GridCells.msg b/nav_msgs/msg/GridCells.msg index de68657b..6d87c0f1 100644 --- a/nav_msgs/msg/GridCells.msg +++ b/nav_msgs/msg/GridCells.msg @@ -3,4 +3,5 @@ std_msgs/Header header float32 cell_width float32 cell_height +# Each cell is represented by the Point at the center of the cell geometry_msgs/Point[] cells diff --git a/nav_msgs/msg/MapMetaData.msg b/nav_msgs/msg/MapMetaData.msg index 9f37e3f5..1c11e290 100644 --- a/nav_msgs/msg/MapMetaData.msg +++ b/nav_msgs/msg/MapMetaData.msg @@ -13,5 +13,5 @@ uint32 width uint32 height # The origin of the map [m, m, rad]. This is the real-world pose of the -# cell (0,0) in the map. +# bottom left corner of cell (0,0) in the map. geometry_msgs/Pose origin diff --git a/nav_msgs/msg/OccupancyGrid.msg b/nav_msgs/msg/OccupancyGrid.msg index 2cccffd4..abbd189b 100644 --- a/nav_msgs/msg/OccupancyGrid.msg +++ b/nav_msgs/msg/OccupancyGrid.msg @@ -1,10 +1,13 @@ -# This represents a 2-D grid map, in which each cell represents the probability of occupancy. - +# This represents a 2-D grid map std_msgs/Header header # MetaData for the map MapMetaData info -# The map data, in row-major order, starting with (0,0). Occupancy -# probabilities are in the range [0,100]. Unknown is -1. +# The map data, in row-major order, starting with (0,0). +# Cell (1, 0) will be listed second, representing the next cell in the x direction. +# Cell (0, 1) will be at the index equal to info.width, followed by (1, 1). +# The values inside are application dependent, but frequently, +# 0 represents unoccupied, 1 represents definitely occupied, and +# -1 represents unknown. int8[] data