Template Class BaseOccupancyGrid2
Defined in File occupancy_grid.hpp
Inheritance Relationships
Base Type
public beluga::BaseLinearGrid2< Derived >
(Template Class BaseLinearGrid2)
Class Documentation
-
template<typename Derived>
class BaseOccupancyGrid2 : public beluga::BaseLinearGrid2<Derived> Occupancy 2D grid base type.
When instantiated, it satisfies Beluga named requirements: OccupancyGrid2d.
- Template Parameters:
Derived – Concrete occupancy grid type. It must define
Derived::origin()
,Derived::width()
,Derived::height()
,Derived::resolution()
,Derived::data_at(std::size_t)
,Derived::index_at(int, int)
,Derived::data()
, andDerived::value_traits()
as described in Beluga named requirements: OccupancyGrid2d.
Public Types
Public Functions
-
inline bool free_at(std::size_t index) const
Checks if cell is free.
Note cells not included in the grid are non-free too.
- Parameters:
index – Grid cell index.
-
inline bool free_at(int xi, int yi) const
Checks if cell is free.
Note cells not included in the grid are non-free too.
- Parameters:
xi – Grid cell x-axis coordinate.
yi – Grid cell y-axis coordinate.
-
inline bool free_at(const Eigen::Vector2i &pi) const
Checks if cell is free.
Note cells not included in the grid are non-free too.
- Parameters:
pi – Grid cell coordinates.
-
inline bool free_near(double x, double y) const
Checks if nearest cell is free.
Note cells not included in the grid are non-free too.
- Parameters:
x – Plane x-axis coordinate.
y – Plane y-axis coordinate.
-
inline bool free_near(const Eigen::Vector2d &p) const
Checks if nearest cell is free.
Note cells not included in the grid are non-free too.
- Parameters:
p – Plane coordinates.
-
inline auto coordinates_at(std::size_t index, Frame frame) const
Compute plane coordinates given grid cell coordinates.
- Parameters:
index – Grid cell index.
frame – Plane coordinate frame.
- Returns:
Plane coordinates in the corresponding
frame
.
-
template<class Range>
inline auto coordinates_for(Range &&cells, Frame frame) const Compute plane coordinates for a range of grid cells.
- Parameters:
cells – Range of grid cell indices or coordinates.
frame – Plane coordinate frame.
- Returns:
Range of plane coordinates in the corresponding
frame
.
-
inline auto free_cells() const
Retrieves range of free grid cell indices.
-
inline auto obstacle_mask() const
Retrieves a mask over occupied cells in the grid.
-
inline auto unknown_mask() const
Retrieves a mask over unknown cells in the grid.