38 #ifndef NAV2_UTIL__OCC_GRID_UTILS_HPP_
39 #define NAV2_UTIL__OCC_GRID_UTILS_HPP_
41 #include "nav_msgs/msg/occupancy_grid.hpp"
56 inline bool worldToMap(
57 nav_msgs::msg::OccupancyGrid::ConstSharedPtr map,
58 const double wx,
const double wy,
unsigned int & mx,
unsigned int & my)
60 const double origin_x = map->info.origin.position.x;
61 const double origin_y = map->info.origin.position.y;
62 const double resolution = map->info.resolution;
63 const unsigned int size_x = map->info.width;
64 const unsigned int size_y = map->info.height;
66 if (wx < origin_x || wy < origin_y) {
70 mx =
static_cast<unsigned int>((wx - origin_x) / resolution);
71 my =
static_cast<unsigned int>((wy - origin_y) / resolution);
72 if (mx >= size_x || my >= size_y) {
86 inline void mapToWorld(
87 nav_msgs::msg::OccupancyGrid::ConstSharedPtr map,
88 const unsigned int mx,
const unsigned int my,
double & wx,
double & wy)
90 const double origin_x = map->info.origin.position.x;
91 const double origin_y = map->info.origin.position.y;
92 const double resolution = map->info.resolution;
94 wx = origin_x + (mx + 0.5) * resolution;
95 wy = origin_y + (my + 0.5) * resolution;