|
Fawkes API
Fawkes Development Version
|
Occupancy Grid class for general use. More...
#include <>>

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... | |
| Probability & | operator() (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... | |
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 35 of file occupancygrid.h.
| fawkes::OccupancyGrid::OccupancyGrid | ( | int | width, |
| int | height, | ||
| int | cell_width = 5, |
||
| int | cell_height = 5 |
||
| ) |
Constructs an empty occupancy grid.
| width | the width of the grid in # of cells |
| height | the height of the cells in # of cells |
| cell_width | the cell width in cm |
| cell_height | the cell height in cm |
Definition at line 41 of file occupancygrid.cpp.
References cell_height_, cell_width_, height_, init_grid(), and width_.
|
virtual |
| void fawkes::OccupancyGrid::fill | ( | Probability | prob | ) |
Resets all occupancy probabilities.
| prob | the occupancy probability the grid will become filled with |
Definition at line 147 of file occupancygrid.cpp.
References height_, fawkes::isProb(), occupancy_probs_, and width_.
Referenced by init_grid().
| int fawkes::OccupancyGrid::get_cell_height | ( | ) |
Get the cell height (in cm)
Get the cell height.
Definition at line 70 of file occupancygrid.cpp.
References cell_height_.
Referenced by fawkes::EscapePotentialFieldDriveModule::update(), and fawkes::EscapePotentialFieldOmniDriveModule::update().
| int fawkes::OccupancyGrid::get_cell_width | ( | ) |
Get the cell width (in cm)
Get the cell width.
Definition at line 61 of file occupancygrid.cpp.
References cell_width_.
Referenced by fawkes::EscapePotentialFieldDriveModule::update(), and fawkes::EscapePotentialFieldOmniDriveModule::update().
| int fawkes::OccupancyGrid::get_height | ( | ) |
Get the height of the grid.
Definition at line 88 of file occupancygrid.cpp.
References height_.
Referenced by fawkes::AStarColli::AStarColli(), fawkes::EscapePotentialFieldDriveModule::update(), and fawkes::EscapePotentialFieldOmniDriveModule::update().
| Probability fawkes::OccupancyGrid::get_prob | ( | int | x, |
| int | y | ||
| ) |
Get the occupancy probability of a cell.
| x | the x-position of the cell |
| y | the y-position of the cell |
Definition at line 164 of file occupancygrid.cpp.
References height_, occupancy_probs_, and width_.
Referenced by fawkes::AStarColli::remove_target_from_obstacle(), fawkes::EscapePotentialFieldDriveModule::update(), fawkes::EscapePotentialFieldOmniDriveModule::update(), and fawkes::Search::update().
| int fawkes::OccupancyGrid::get_width | ( | ) |
Get the width of the grid.
Definition at line 79 of file occupancygrid.cpp.
References width_.
Referenced by fawkes::AStarColli::AStarColli(), fawkes::EscapePotentialFieldDriveModule::update(), and fawkes::EscapePotentialFieldOmniDriveModule::update().
| 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 186 of file occupancygrid.cpp.
References fill(), height_, occupancy_probs_, and width_.
Referenced by fawkes::LaserOccupancyGrid::LaserOccupancyGrid(), OccupancyGrid(), set_height(), and set_width().
| Probability & fawkes::OccupancyGrid::operator() | ( | const int | x, |
| const int | y | ||
| ) |
Get the occupancy probability of a cell.
Operator (), get occupancy probability of a cell.
| x | the x-position of the cell |
| y | the y-position of the cell |
Definition at line 179 of file occupancygrid.cpp.
References occupancy_probs_.
| void fawkes::OccupancyGrid::set_cell_height | ( | int | height | ) |
Resets the cell height (in cm)
Resets the cell height.
| height | the height of the cells in cm |
Definition at line 106 of file occupancygrid.cpp.
References cell_height_.
| void fawkes::OccupancyGrid::set_cell_width | ( | int | width | ) |
Resets the cell width (in cm)
Resets the cell width.
| width | the width of the cells in cm |
Definition at line 97 of file occupancygrid.cpp.
References cell_width_.
| void fawkes::OccupancyGrid::set_height | ( | int | height | ) |
Resets the height of the grid and constructs a new empty grid.
| height | the height of the grid in # of cells |
Definition at line 125 of file occupancygrid.cpp.
References height_, and init_grid().
|
virtual |
Reset the occupancy probability of a cell.
| x | the x-position of the cell |
| y | the y-position of the cell |
| prob | the occupancy probability of cell (x,y) |
Definition at line 137 of file occupancygrid.cpp.
References height_, fawkes::isProb(), occupancy_probs_, and width_.
| void fawkes::OccupancyGrid::set_width | ( | int | width | ) |
Resets the width of the grid and constructs a new empty grid.
| width | the cell width in cm |
Definition at line 115 of file occupancygrid.cpp.
References init_grid(), and width_.
|
protected |
Cell height in cm.
Definition at line 85 of file occupancygrid.h.
Referenced by get_cell_height(), OccupancyGrid(), fawkes::LaserOccupancyGrid::set_base_offset(), and set_cell_height().
|
protected |
Cell width in cm.
Definition at line 84 of file occupancygrid.h.
Referenced by get_cell_width(), OccupancyGrid(), fawkes::LaserOccupancyGrid::set_base_offset(), and set_cell_width().
|
protected |
Height of the grid in # cells.
Definition at line 87 of file occupancygrid.h.
Referenced by fill(), get_height(), get_prob(), init_grid(), OccupancyGrid(), set_height(), set_prob(), and fawkes::LaserOccupancyGrid::update_occ_grid().
| std::vector<std::vector<Probability> > fawkes::OccupancyGrid::occupancy_probs_ |
The occupancy probability of the cells in a 2D array.
Definition at line 81 of file occupancygrid.h.
Referenced by fill(), get_prob(), init_grid(), operator()(), set_prob(), fawkes::LaserOccupancyGrid::update_occ_grid(), and ~OccupancyGrid().
|
protected |
Width of the grid in # cells.
Definition at line 86 of file occupancygrid.h.
Referenced by fill(), get_prob(), get_width(), init_grid(), OccupancyGrid(), set_prob(), set_width(), and fawkes::LaserOccupancyGrid::update_occ_grid().