#include <nav_grid_info.h>
Public Member Functions | |
bool | operator!= (const NavGridInfo &info) const |
bool | operator== (const NavGridInfo &info) const |
comparison operator that requires all fields are equal More... | |
std::string | toString () const |
String representation of this object. More... | |
Public Attributes | |
std::string | frame_id = "map" |
unsigned int | height = 0 |
double | origin_x = 0.0 |
The origin defines the coordinates of minimum corner of cell (0,0) in the grid. More... | |
double | origin_y = 0.0 |
double | resolution = 1.0 |
unsigned int | width = 0 |
This class defines a way to discretize a finite section of the world into a grid. It contains similar information to the ROS msg nav_msgs/MapMetaData (aka the info field of nav_msgs/OccupancyGrid) except the map_load_time is removed, the geometry is simplified from a Pose to xy coordinates, and the frame_id is added.
Definition at line 49 of file nav_grid_info.h.
|
inline |
Definition at line 69 of file nav_grid_info.h.
|
inline |
comparison operator that requires all fields are equal
Definition at line 63 of file nav_grid_info.h.
|
inline |
String representation of this object.
Definition at line 77 of file nav_grid_info.h.
std::string nav_grid::NavGridInfo::frame_id = "map" |
Definition at line 56 of file nav_grid_info.h.
unsigned int nav_grid::NavGridInfo::height = 0 |
Definition at line 54 of file nav_grid_info.h.
double nav_grid::NavGridInfo::origin_x = 0.0 |
The origin defines the coordinates of minimum corner of cell (0,0) in the grid.
Definition at line 57 of file nav_grid_info.h.
double nav_grid::NavGridInfo::origin_y = 0.0 |
Definition at line 58 of file nav_grid_info.h.
double nav_grid::NavGridInfo::resolution = 1.0 |
Definition at line 55 of file nav_grid_info.h.
unsigned int nav_grid::NavGridInfo::width = 0 |
Definition at line 53 of file nav_grid_info.h.