Public Types | Public Member Functions | List of all members
beluga::BaseOccupancyGrid2< Derived > Class Template Reference

Occupancy 2D grid base type. More...

#include <occupancy_grid.hpp>

Inheritance diagram for beluga::BaseOccupancyGrid2< Derived >:
Inheritance graph
[legend]

Public Types

enum  Frame : std::uint8_t { Frame::kLocal, Frame::kGlobal }
 Coordinate frames. More...
 

Public Member Functions

auto coordinates_at (std::size_t index, Frame frame) const
 Compute plane coordinates given grid cell coordinates. More...
 
template<class Range >
auto coordinates_for (Range &&cells, Frame frame) const
 Compute plane coordinates for a range of grid cells. More...
 
bool free_at (const Eigen::Vector2i &pi) const
 Checks if cell is free. More...
 
bool free_at (int xi, int yi) const
 Checks if cell is free. More...
 
bool free_at (std::size_t index) const
 Checks if cell is free. More...
 
auto free_cells () const
 Retrieves range of free grid cell indices. More...
 
bool free_near (const Eigen::Vector2d &p) const
 Checks if nearest cell is free. More...
 
bool free_near (double x, double y) const
 Checks if nearest cell is free. More...
 
auto obstacle_data () const
 Retrieves grid data using true booleans for obstacles. More...
 
- Public Member Functions inherited from beluga::BaseLinearGrid2< Derived >
Eigen::Vector2d coordinates_at (std::size_t index) const
 Compute plane coordinates given a grid cell index. More...
 
auto data_at (std::size_t index) const
 Gets cell data, if included. More...
 
std::size_t index_at (const Eigen::Vector2i &pi) const
 Computes index for given grid cell coordinates. More...
 
std::size_t index_at (int xi, int yi) const
 Computes index for given grid cell coordinates. More...
 
auto neighborhood4 (std::size_t index) const
 Computes 4-connected neighborhood for cell. More...
 
- Public Member Functions inherited from beluga::BaseDenseGrid2< Derived >
bool contains (const Eigen::Vector2i &pi) const
 Checks if a cell is included in the grid. More...
 
bool contains (int xi, int yi) const
 Checks if a cell is included in the grid. More...
 
auto data_at (const Eigen::Vector2i &pi) const
 Gets cell data, if included. More...
 
auto data_at (int xi, int yi) const
 Gets cell data, if included. More...
 
auto data_near (const Eigen::Vector2d &p) const
 Gets nearest cell data, if included. More...
 
auto data_near (double x, double y) const
 Gets nearest cell data, if included. More...
 
auto neighborhood4 (const Eigen::Vector2i &pi) const
 Computes 4-connected neighborhood for cell. More...
 
auto neighborhood4 (int xi, int yi) const
 Computes 4-connected neighborhood for cell. More...
 
- Public Member Functions inherited from beluga::BaseRegularGrid< Derived, NDim >
Eigen::Vector< int, NDim > cell_near (const Eigen::Vector< double, NDim > &p) const
 Compute nearest grid cell coordinates given plane coordinates. More...
 
Eigen::Vector< double, NDim > coordinates_at (const Eigen::Vector< int, NDim > &pi) const
 Compute plane coordinates given grid cell coordinates. More...
 
template<class Range >
auto coordinates_for (Range &&cells) const
 Compute plane coordinates given a range of cell coordinates. More...
 

Detailed Description

template<typename Derived>
class beluga::BaseOccupancyGrid2< Derived >

Occupancy 2D grid base type.

When instantiated, it satisfies Beluga named requirements: OccupancyGrid2d.

Template Parameters
DerivedConcrete 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(), and Derived::value_traits() as described in Beluga named requirements: OccupancyGrid2d.

Definition at line 85 of file occupancy_grid.hpp.

Member Enumeration Documentation

◆ Frame

template<typename Derived >
enum beluga::BaseOccupancyGrid2::Frame : std::uint8_t
strong

Coordinate frames.

Enumerator
kLocal 
kGlobal 

Definition at line 88 of file occupancy_grid.hpp.

Member Function Documentation

◆ coordinates_at()

template<typename Derived >
auto beluga::BaseOccupancyGrid2< Derived >::coordinates_at ( std::size_t  index,
Frame  frame 
) const
inline

Compute plane coordinates given grid cell coordinates.

Parameters
indexGrid cell index.
framePlane coordinate frame.
Returns
Plane coordinates in the corresponding frame.

Definition at line 148 of file occupancy_grid.hpp.

◆ coordinates_for()

template<typename Derived >
template<class Range >
auto beluga::BaseOccupancyGrid2< Derived >::coordinates_for ( Range &&  cells,
Frame  frame 
) const
inline

Compute plane coordinates for a range of grid cells.

Parameters
cellsRange of grid cell indices or coordinates.
framePlane coordinate frame.
Returns
Range of plane coordinates in the corresponding frame.

Definition at line 163 of file occupancy_grid.hpp.

◆ free_at() [1/3]

template<typename Derived >
bool beluga::BaseOccupancyGrid2< Derived >::free_at ( const Eigen::Vector2i &  pi) const
inline

Checks if cell is free.

Note cells not included in the grid are non-free too.

Parameters
piGrid cell coordinates.

Definition at line 119 of file occupancy_grid.hpp.

◆ free_at() [2/3]

template<typename Derived >
bool beluga::BaseOccupancyGrid2< Derived >::free_at ( int  xi,
int  yi 
) const
inline

Checks if cell is free.

Note cells not included in the grid are non-free too.

Parameters
xiGrid cell x-axis coordinate.
yiGrid cell y-axis coordinate.

Definition at line 111 of file occupancy_grid.hpp.

◆ free_at() [3/3]

template<typename Derived >
bool beluga::BaseOccupancyGrid2< Derived >::free_at ( std::size_t  index) const
inline

Checks if cell is free.

Note cells not included in the grid are non-free too.

Parameters
indexGrid cell index.

Definition at line 96 of file occupancy_grid.hpp.

◆ free_cells()

template<typename Derived >
auto beluga::BaseOccupancyGrid2< Derived >::free_cells ( ) const
inline

Retrieves range of free grid cell indices.

Definition at line 169 of file occupancy_grid.hpp.

◆ free_near() [1/2]

template<typename Derived >
bool beluga::BaseOccupancyGrid2< Derived >::free_near ( const Eigen::Vector2d p) const
inline

Checks if nearest cell is free.

Note cells not included in the grid are non-free too.

Parameters
pPlane coordinates.

Definition at line 138 of file occupancy_grid.hpp.

◆ free_near() [2/2]

template<typename Derived >
bool beluga::BaseOccupancyGrid2< Derived >::free_near ( double  x,
double  y 
) const
inline

Checks if nearest cell is free.

Note cells not included in the grid are non-free too.

Parameters
xPlane x-axis coordinate.
yPlane y-axis coordinate.

Definition at line 128 of file occupancy_grid.hpp.

◆ obstacle_data()

template<typename Derived >
auto beluga::BaseOccupancyGrid2< Derived >::obstacle_data ( ) const
inline

Retrieves grid data using true booleans for obstacles.

Definition at line 178 of file occupancy_grid.hpp.


The documentation for this class was generated from the following file:


beluga
Author(s):
autogenerated on Tue Jul 16 2024 02:59:54