Beluga named requirements: OccupancyGrid2d

Occupancy grids model obstacle probability. These grids also define their own frame in the grid embedding space, adding so called global coordinates to regular (aka local) coordinates. Occupancy grids as defined in Beluga are linear grids, meaning they satisfy Beluga named requirements: LinearGrid2 requirements.

A type G satisfies OccupancyGrid2d requirements if it satisfies Beluga named requirements: LinearGrid2 and given g a possible const instance of G:

  • g.value_traits() returns a value t of type T such that given a grid cell data value v:

    • t.is_free(v) returns true if the value is consistent with a free grid cell;

    • t.is_occupied(v) returns true if the value is consistent with an occupied grid cell;

  • g.origin() returns the transform, of Sophus::SE2d type, from the global to local frame in the grid embedding space;

  • given possibly const grid cell index i of std::size_t type, g.free_at(i) returns true if such cell is free;

  • given possibly const grid cell coordinates xi and yi of type int, g.free_at(xi, yi) returns true if such cell is free;

  • given possibly const grid cell coordinates pi of Eigen::Vector2i type, g.free_at(p) returns true if such cell is free;

  • given possibly const embedding space coordinates x and y of type double, g.free_near(x, y) returns true if the nearest cell is free;

  • given possibly const embedding space coordinates p of Eigen::Vector2d type, g.free_near(p) returns true if the nearest cell is free;

  • given possibly const grid cell index i of std::size_t type and frame f, g.coordinates_at(i, f) returns embedding space coordinates in the corresponding frame as an Eigen::Vector2d value;

  • given a possibly const range r of grid cell coordinates or indices and frame f, g.coordinates_for(r, f) returns a range of embedding space coordinates in the corresponding frame as Eigen::Vector2d values;

  • g.free_cells() returns a range of std::size_t indices to free grid cells;

  • g.obstacle_data() returns a range of bool values, representing grid cell occupancy;