Fawkes API  Fawkes Development Version
fawkes::OccupancyGrid Class Reference

#include <>>

Inheritance diagram for fawkes::OccupancyGrid:

Public Member Functions

 OccupancyGrid (int width, int height, int cell_width=5, int cell_height=5)
 Constructs an empty occupancy grid. More...
 
virtual ~OccupancyGrid ()
 Destructor. More...
 
int get_cell_width ()
 Get the cell width (in cm) More...
 
int get_cell_height ()
 Get the cell height (in cm) More...
 
int get_width ()
 Get the width of the grid. More...
 
int get_height ()
 Get the height of the grid. More...
 
void set_cell_width (int cell_width)
 Resets the cell width (in cm) More...
 
void set_cell_height (int cell_height)
 Resets the cell height (in cm) More...
 
void set_width (int width)
 Resets the width of the grid and constructs a new empty grid. More...
 
void set_height (int height)
 Resets the height of the grid and constructs a new empty grid. More...
 
virtual void set_prob (int x, int y, Probability prob)
 Reset the occupancy probability of a cell. More...
 
void fill (Probability prob)
 Resets all occupancy probabilities. More...
 
Probability get_prob (int x, int y)
 Get the occupancy probability of a cell. More...
 
Probabilityoperator() (const int x, const int y)
 Get the occupancy probability of a cell. More...
 
void init_grid ()
 Init a new empty grid with the predefined parameters *‍/. More...
 

Public Attributes

std::vector< std::vector< Probability > > occupancy_probs_
 The occupancy probability of the cells in a 2D array. More...
 

Protected Attributes

int cell_width_
 Cell width in cm. More...
 
int cell_height_
 Cell height in cm. More...
 
int width_
 Width of the grid in # cells. More...
 
int height_
 Height of the grid in # cells. More...
 

Detailed Description

Occupancy Grid class for general use. Many derivated classes exist, which are usually used instead of this general class. Note: the coord system is assumed to map x onto width an y onto height, with x being the first coordinate !

Definition at line 39 of file occupancygrid.h.

Constructor & Destructor Documentation

◆ OccupancyGrid()

fawkes::OccupancyGrid::OccupancyGrid ( int  width,
int  height,
int  cell_width = 5,
int  cell_height = 5 
)

Constructs an empty occupancy grid.

Parameters
widththe width of the grid in # of cells
heightthe height of the cells in # of cells
cell_widththe cell width in cm
cell_heightthe cell height in cm

Definition at line 45 of file occupancygrid.cpp.

◆ ~OccupancyGrid()

fawkes::OccupancyGrid::~OccupancyGrid ( )
virtual

Destructor.

Definition at line 56 of file occupancygrid.cpp.

References cell_width_.

Member Function Documentation

◆ fill()

void fawkes::OccupancyGrid::fill ( Probability  prob)

Resets all occupancy probabilities.

Parameters
probthe occupancy probability the grid will become filled with

Definition at line 151 of file occupancygrid.cpp.

References occupancy_probs_.

◆ get_cell_height()

int fawkes::OccupancyGrid::get_cell_height ( )

Get the cell height (in cm)

Get the cell height.

Returns
the height of the cells in cm

Definition at line 74 of file occupancygrid.cpp.

References width_.

◆ get_cell_width()

int fawkes::OccupancyGrid::get_cell_width ( )

Get the cell width (in cm)

Get the cell width.

Returns
the cell width in cm

Definition at line 65 of file occupancygrid.cpp.

References cell_height_.

◆ get_height()

int fawkes::OccupancyGrid::get_height ( )

Get the height of the grid.

Returns
the height of the grid in # cells

Definition at line 92 of file occupancygrid.cpp.

References cell_width_.

Referenced by fawkes::AStarColli::AStarColli().

◆ get_prob()

Probability fawkes::OccupancyGrid::get_prob ( int  x,
int  y 
)

Get the occupancy probability of a cell.

Parameters
xthe x-position of the cell
ythe y-position of the cell
Returns
the occupancy probability of cell (x,y)

Definition at line 168 of file occupancygrid.cpp.

Referenced by fawkes::AStarColli::remove_target_from_obstacle().

◆ get_width()

int fawkes::OccupancyGrid::get_width ( )

Get the width of the grid.

Returns
the width of the grid in # of cells

Definition at line 83 of file occupancygrid.cpp.

References height_.

Referenced by fawkes::AStarColli::AStarColli().

◆ init_grid()

void fawkes::OccupancyGrid::init_grid ( )

Init a new empty grid with the predefined parameters *‍/.

Init a new empty grid with the predefined parameters.

Definition at line 190 of file occupancygrid.cpp.

Referenced by fawkes::LaserOccupancyGrid::LaserOccupancyGrid(), and set_cell_height().

◆ operator()()

Probability & fawkes::OccupancyGrid::operator() ( const int  x,
const int  y 
)

Get the occupancy probability of a cell.

Operator (), get occupancy probability of a cell.

Parameters
xthe x-position of the cell
ythe y-position of the cell
Returns
the occupancy probability of cell (x,y)

Definition at line 183 of file occupancygrid.cpp.

References occupancy_probs_.

◆ set_cell_height()

void fawkes::OccupancyGrid::set_cell_height ( int  height)

Resets the cell height (in cm)

Resets the cell height.

Parameters
heightthe height of the cells in cm

Definition at line 110 of file occupancygrid.cpp.

References init_grid(), and width_.

◆ set_cell_width()

void fawkes::OccupancyGrid::set_cell_width ( int  width)

Resets the cell width (in cm)

Resets the cell width.

Parameters
widththe width of the cells in cm

Definition at line 101 of file occupancygrid.cpp.

References cell_height_.

◆ set_height()

void fawkes::OccupancyGrid::set_height ( int  height)

Resets the height of the grid and constructs a new empty grid.

Parameters
heightthe height of the grid in # of cells

Definition at line 129 of file occupancygrid.cpp.

◆ set_prob()

void fawkes::OccupancyGrid::set_prob ( int  x,
int  y,
Probability  prob 
)
virtual

Reset the occupancy probability of a cell.

Parameters
xthe x-position of the cell
ythe y-position of the cell
probthe occupancy probability of cell (x,y)

Definition at line 141 of file occupancygrid.cpp.

◆ set_width()

void fawkes::OccupancyGrid::set_width ( int  width)

Resets the width of the grid and constructs a new empty grid.

Parameters
widththe cell width in cm

Definition at line 119 of file occupancygrid.cpp.

Member Data Documentation

◆ cell_height_

int fawkes::OccupancyGrid::cell_height_
protected

◆ cell_width_

int fawkes::OccupancyGrid::cell_width_
protected

◆ height_

int fawkes::OccupancyGrid::height_
protected

Height of the grid in # cells.

Definition at line 91 of file occupancygrid.h.

Referenced by get_width().

◆ occupancy_probs_

std::vector<std::vector<Probability> > fawkes::OccupancyGrid::occupancy_probs_

The occupancy probability of the cells in a 2D array.

Definition at line 85 of file occupancygrid.h.

Referenced by fill(), and operator()().

◆ width_

int fawkes::OccupancyGrid::width_
protected

Width of the grid in # cells.

Definition at line 90 of file occupancygrid.h.

Referenced by fawkes::LaserOccupancyGrid::get_cell_costs(), get_cell_height(), and set_cell_height().


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