19#ifndef EASYNAV_PLANNER__SIMPLEMAP_HPP_
20#define EASYNAV_PLANNER__SIMPLEMAP_HPP_
25#include "nav_msgs/msg/occupancy_grid.hpp"
59 double origin_y,
bool initial_value =
false);
64 size_t width()
const {
return width_;}
69 size_t height()
const {
return height_;}
90 uint8_t
at(
int x,
int y)
const;
96 uint8_t &
at(
int x,
int y);
103 void fill(uint8_t value);
184 void print(
bool view_data =
false)
const;
200 std::shared_ptr<SimpleMap>
downsample(
double new_resolution)
const;
208 std::vector<uint8_t> data_;
210 int index(
int x,
int y)
const;
211 void check_bounds(
size_t x,
size_t y)
const;
Simple 2D uint8_t grid using basic C++ types, with full metric conversion support.
Definition SimpleMap.hpp:38
double origin_y() const
Returns the metric origin y coordinate.
Definition SimpleMap.hpp:84
SimpleMap()
Default constructor.
Definition SimpleMap.cpp:33
void from_occupancy_grid(const nav_msgs::msg::OccupancyGrid &grid_msg)
Load map data and metadata from a nav_msgs::msg::OccupancyGrid message.
Definition SimpleMap.cpp:144
std::shared_ptr< SimpleMap > downsample_factor(int factor) const
Creates a downsampled version of the map by an integer factor.
Definition SimpleMap.cpp:269
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.
Definition SimpleMap.cpp:38
std::pair< int, int > metric_to_cell(double mx, double my) const
Converts real-world metric coordinates (meters) to a cell index (x, y).
Definition SimpleMap.cpp:107
bool check_bounds_metric(double mx, double my) const
Checks if given metric coordinates are within the map bounds.
Definition SimpleMap.cpp:83
void print(bool view_data=false) const
Prints metadata and optionally all map cell values with coordinates.
Definition SimpleMap.cpp:248
std::pair< double, double > cell_to_metric(int x, int y) const
Converts a cell index (x, y) to real-world metric coordinates (meters).
Definition SimpleMap.cpp:99
std::shared_ptr< SimpleMap > downsample(double new_resolution) const
Creates a downsampled version of the map to match a target resolution.
Definition SimpleMap.cpp:304
double origin_x() const
Returns the metric origin x coordinate.
Definition SimpleMap.hpp:79
size_t width() const
Returns the width (number of columns) of the map.
Definition SimpleMap.hpp:64
void fill(uint8_t value)
Set all cells to a given value.
Definition SimpleMap.cpp:66
void to_occupancy_grid(nav_msgs::msg::OccupancyGrid &grid_msg) const
Updates a nav_msgs::msg::OccupancyGrid message from the SimpleMap contents.
Definition SimpleMap.cpp:119
bool load_from_file(const std::string &path)
Loads the map from a file, reading metadata and cell data.
Definition SimpleMap.cpp:188
void deep_copy(const SimpleMap &other)
Performs a deep copy from another SimpleMap.
Definition SimpleMap.cpp:72
uint8_t at(int x, int y) const
Access a cell (const) at (x, y).
Definition SimpleMap.cpp:51
bool save_to_file(const std::string &path) const
Saves the map to a file, including metadata and cell data.
Definition SimpleMap.cpp:164
size_t height() const
Returns the height (number of rows) of the map.
Definition SimpleMap.hpp:69
double resolution() const
Returns the resolution (cell size in meters).
Definition SimpleMap.hpp:74
Provides a mapping for often used cost values.
Definition cost_values.hpp:41