|
| void | bresenham2D (unsigned int abs_da, unsigned int abs_db, int error_b, int offset_a, int offset_b, unsigned int offset) |
| |
| void | bresenhamCellFree (unsigned int offset) |
| |
| void | bresenhamCellOcc (unsigned int offset) |
| |
| float | getGridProbabilityMap (int index) const |
| |
| float | getObstacleThreshold () const |
| |
| bool | isFree (int xMap, int yMap) const |
| |
| bool | isFree (int index) const |
| |
| bool | isOccupied (int xMap, int yMap) const |
| |
| bool | isOccupied (int index) const |
| |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | OccGridMapBase (float mapResolution, const Eigen::Vector2i &size, const Eigen::Vector2f &offset) |
| |
| void | setUpdateFreeFactor (float factor) |
| |
| void | setUpdateOccupiedFactor (float factor) |
| |
| void | updateByScan (const DataContainer &dataContainer, const Eigen::Vector3f &robotPoseWorld) |
| |
| void | updateLineBresenhami (const Eigen::Vector2i &beginMap, const Eigen::Vector2i &endMap, unsigned int max_length=UINT_MAX) |
| |
| void | updateSetFree (int index) |
| |
| void | updateSetOccupied (int index) |
| |
| void | updateUnsetFree (int index) |
| |
| virtual | ~OccGridMapBase () |
| |
| void | allocateArray (const Eigen::Vector2i &newMapDims) |
| |
| void | clear () |
| |
| void | deleteArray () |
| |
| ConcreteCellType & | getCell (int x, int y) |
| |
| const ConcreteCellType & | getCell (int x, int y) const |
| |
| ConcreteCellType & | getCell (int index) |
| |
| const ConcreteCellType & | getCell (int index) const |
| |
| float | getCellLength () const |
| |
| Eigen::Vector2f | getMapCoords (const Eigen::Vector2f &worldCoords) const |
| |
| Eigen::Vector3f | getMapCoordsPose (const Eigen::Vector3f &worldPose) const |
| |
| const Eigen::Vector2i & | getMapDimensions () const |
| |
| const MapDimensionProperties & | getMapDimProperties () const |
| |
| bool | getMapExtends (int &xMax, int &yMax, int &xMin, int &yMin) const |
| |
| const Eigen::Affine2f & | getMapTworld () const |
| |
| float | getScaleToMap () const |
| |
| int | getSizeX () const |
| |
| int | getSizeY () const |
| |
| int | getUpdateIndex () const |
| |
| Eigen::Vector2f | getWorldCoords (const Eigen::Vector2f &mapCoords) const |
| |
| Eigen::Vector3f | getWorldCoordsPose (const Eigen::Vector3f &mapPose) const |
| |
| const Eigen::Affine2f & | getWorldTmap () const |
| |
| const Eigen::Affine3f & | getWorldTmap3D () const |
| |
| | GridMapBase (float mapResolution, const Eigen::Vector2i &size, const Eigen::Vector2f &offset) |
| |
| | GridMapBase (const GridMapBase &other) |
| |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW bool | hasGridValue (int x, int y) const |
| |
| GridMapBase & | operator= (const GridMapBase &other) |
| |
| bool | pointOutOfMapBounds (const Eigen::Vector2f &pointMapCoords) const |
| |
| virtual void | reset () |
| |
| void | setDimensionProperties (const Eigen::Vector2f &topLeftOffsetIn, const Eigen::Vector2i &mapDimensionsIn, float cellLengthIn) |
| |
| void | setDimensionProperties (const MapDimensionProperties &newMapDimProps) |
| |
| void | setMapGridSize (const Eigen::Vector2i &newMapDims) |
| |
| void | setMapTransformation (const Eigen::Vector2f &topLeftOffset, float cellLength) |
| |
| void | setUpdated () |
| |
| virtual | ~GridMapBase () |
| |
template<typename ConcreteCellType, typename ConcreteGridFunctions>
class hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >
Definition at line 42 of file OccGridMapBase.h.