EasyNav Simple Stack
|
Simple 2D uint8_t grid using basic C++ types, with full metric conversion support. More...
#include <SimpleMap.hpp>
Public Member Functions | |
uint8_t & | at (int x, int y) |
Access a cell (non-const) at (x, y). | |
uint8_t | at (int x, int y) const |
Access a cell (const) at (x, y). | |
std::pair< double, double > | cell_to_metric (int x, int y) const |
Converts a cell index (x, y) to real-world metric coordinates (meters). | |
bool | check_bounds_metric (double mx, double my) const |
Checks if given metric coordinates are within the map bounds. | |
void | deep_copy (const SimpleMap &other) |
Performs a deep copy from another SimpleMap. | |
std::shared_ptr< SimpleMap > | downsample (double new_resolution) const |
Creates a downsampled version of the map to match a target resolution. | |
std::shared_ptr< SimpleMap > | downsample_factor (int factor) const |
Creates a downsampled version of the map by an integer factor. | |
void | fill (uint8_t value) |
Set all cells to a given value. | |
void | from_occupancy_grid (const nav_msgs::msg::OccupancyGrid &grid_msg) |
Load map data and metadata from a nav_msgs::msg::OccupancyGrid message. | |
size_t | height () const |
Returns the height (number of rows) of the map. | |
void | initialize (int width, int height, double resolution, double origin_x, double origin_y, bool initial_value=false) |
Initialize the map to new dimensions, resolution, and origin. | |
bool | load_from_file (const std::string &path) |
Loads the map from a file, reading metadata and cell data. | |
std::pair< int, int > | metric_to_cell (double mx, double my) const |
Converts real-world metric coordinates (meters) to a cell index (x, y). | |
double | origin_x () const |
Returns the metric origin x coordinate. | |
double | origin_y () const |
Returns the metric origin y coordinate. | |
void | print (bool view_data=false) const |
Prints metadata and optionally all map cell values with coordinates. | |
double | resolution () const |
Returns the resolution (cell size in meters). | |
bool | save_to_file (const std::string &path) const |
Saves the map to a file, including metadata and cell data. | |
SimpleMap () | |
Default constructor. | |
void | to_occupancy_grid (nav_msgs::msg::OccupancyGrid &grid_msg) const |
Updates a nav_msgs::msg::OccupancyGrid message from the SimpleMap contents. | |
size_t | width () const |
Returns the width (number of columns) of the map. | |
Simple 2D uint8_t grid using basic C++ types, with full metric conversion support.
Supports arbitrary metric origins, allowing negative coordinates.
SimpleMap | ( | ) |
Default constructor.
Creates an empty (0x0) SimpleMap with 1.0 meter resolution and origin (0.0, 0.0).
uint8_t & at | ( | int | x, |
int | y ) |
Access a cell (non-const) at (x, y).
std::out_of_range | if (x,y) is out of bounds. |
uint8_t at | ( | int | x, |
int | y ) const |
Access a cell (const) at (x, y).
std::out_of_range | if (x,y) is out of bounds. |
std::pair< double, double > cell_to_metric | ( | int | x, |
int | y ) const |
Converts a cell index (x, y) to real-world metric coordinates (meters).
x | Cell column index. |
y | Cell row index. |
bool check_bounds_metric | ( | double | mx, |
double | my ) const |
Checks if given metric coordinates are within the map bounds.
mx | Metric x coordinate. |
my | Metric y coordinate. |
void deep_copy | ( | const SimpleMap & | other | ) |
std::shared_ptr< SimpleMap > downsample | ( | double | new_resolution | ) | const |
Creates a downsampled version of the map to match a target resolution.
new_resolution | New desired resolution (must be a multiple of current). |
std::shared_ptr< SimpleMap > downsample_factor | ( | int | factor | ) | const |
Creates a downsampled version of the map by an integer factor.
factor | Integer factor (>1) to reduce resolution. |
void fill | ( | uint8_t | value | ) |
Set all cells to a given value.
value | Value to fill the map with. |
void from_occupancy_grid | ( | const nav_msgs::msg::OccupancyGrid & | grid_msg | ) |
Load map data and metadata from a nav_msgs::msg::OccupancyGrid message.
This function resizes the internal grid to match the occupancy grid dimensions, sets the resolution and origin, and copies the data.
grid_msg | The occupancy grid message to load from. |
size_t height | ( | ) | const |
Returns the height (number of rows) of the map.
void initialize | ( | int | width, |
int | height, | ||
double | resolution, | ||
double | origin_x, | ||
double | origin_y, | ||
bool | initial_value = false ) |
Initialize the map to new dimensions, resolution, and origin.
width | Number of columns. |
height | Number of rows. |
resolution | Size of each cell in meters. |
origin_x | Metric X coordinate corresponding to cell (0,0). |
origin_y | Metric Y coordinate corresponding to cell (0,0). |
initial_value | Value to initialize all cells. |
bool load_from_file | ( | const std::string & | path | ) |
Loads the map from a file, reading metadata and cell data.
path | Path to the input file. |
std::pair< int, int > metric_to_cell | ( | double | mx, |
double | my ) const |
Converts real-world metric coordinates (meters) to a cell index (x, y).
mx | Metric x coordinate. |
my | Metric y coordinate. |
std::out_of_range | if resulting indices are out of map bounds. |
double origin_x | ( | ) | const |
Returns the metric origin x coordinate.
double origin_y | ( | ) | const |
Returns the metric origin y coordinate.
void print | ( | bool | view_data = false | ) | const |
Prints metadata and optionally all map cell values with coordinates.
view_data | If true, prints cell-by-cell content with coordinates. Default is false. |
double resolution | ( | ) | const |
Returns the resolution (cell size in meters).
bool save_to_file | ( | const std::string & | path | ) | const |
Saves the map to a file, including metadata and cell data.
path | Path to the output file. |
void to_occupancy_grid | ( | nav_msgs::msg::OccupancyGrid & | grid_msg | ) | const |
Updates a nav_msgs::msg::OccupancyGrid message from the SimpleMap contents.
Cells are mapped as follows:
If the grid dimensions do not match, the message is rdata_esized automatically.
grid_msg | The occupancy grid message to fill or update. |
size_t width | ( | ) | const |
Returns the width (number of columns) of the map.