#include <OccGridMapBase.h>
Public Member Functions | |
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 () |
Protected Attributes | |
ConcreteGridFunctions | concreteGridFunctions |
int | currMarkFreeIndex |
int | currMarkOccIndex |
int | currUpdateIndex |
Definition at line 42 of file OccGridMapBase.h.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::OccGridMapBase | ( | float | mapResolution, |
const Eigen::Vector2i & | size, | ||
const Eigen::Vector2f & | offset | ||
) | [inline] |
Definition at line 50 of file OccGridMapBase.h.
virtual hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::~OccGridMapBase | ( | ) | [inline, virtual] |
Definition at line 57 of file OccGridMapBase.h.
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::bresenham2D | ( | unsigned int | abs_da, |
unsigned int | abs_db, | ||
int | error_b, | ||
int | offset_a, | ||
int | offset_b, | ||
unsigned int | offset | ||
) | [inline] |
Definition at line 243 of file OccGridMapBase.h.
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::bresenhamCellFree | ( | unsigned int | offset | ) | [inline] |
Definition at line 216 of file OccGridMapBase.h.
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::bresenhamCellOcc | ( | unsigned int | offset | ) | [inline] |
Definition at line 226 of file OccGridMapBase.h.
float hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::getGridProbabilityMap | ( | int | index | ) | const [inline] |
Definition at line 74 of file OccGridMapBase.h.
float hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::getObstacleThreshold | ( | ) | const [inline] |
Definition at line 99 of file OccGridMapBase.h.
bool hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::isFree | ( | int | xMap, |
int | yMap | ||
) | const [inline] |
Definition at line 84 of file OccGridMapBase.h.
bool hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::isFree | ( | int | index | ) | const [inline] |
Definition at line 94 of file OccGridMapBase.h.
bool hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::isOccupied | ( | int | xMap, |
int | yMap | ||
) | const [inline] |
Definition at line 79 of file OccGridMapBase.h.
bool hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::isOccupied | ( | int | index | ) | const [inline] |
Definition at line 89 of file OccGridMapBase.h.
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::setUpdateFreeFactor | ( | float | factor | ) | [inline] |
Definition at line 106 of file OccGridMapBase.h.
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::setUpdateOccupiedFactor | ( | float | factor | ) | [inline] |
Definition at line 111 of file OccGridMapBase.h.
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::updateByScan | ( | const DataContainer & | dataContainer, |
const Eigen::Vector3f & | robotPoseWorld | ||
) | [inline] |
Updates the map using the given scan data and robot pose
dataContainer | Contains the laser scan data |
robotPoseWorld | The 2D robot pose in world coordinates |
Definition at line 121 of file OccGridMapBase.h.
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::updateLineBresenhami | ( | const Eigen::Vector2i & | beginMap, |
const Eigen::Vector2i & | endMap, | ||
unsigned int | max_length = UINT_MAX |
||
) | [inline] |
Definition at line 170 of file OccGridMapBase.h.
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::updateSetFree | ( | int | index | ) | [inline] |
Definition at line 64 of file OccGridMapBase.h.
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::updateSetOccupied | ( | int | index | ) | [inline] |
Definition at line 59 of file OccGridMapBase.h.
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::updateUnsetFree | ( | int | index | ) | [inline] |
Definition at line 69 of file OccGridMapBase.h.
ConcreteGridFunctions hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::concreteGridFunctions [protected] |
Definition at line 264 of file OccGridMapBase.h.
int hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::currMarkFreeIndex [protected] |
Definition at line 267 of file OccGridMapBase.h.
int hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::currMarkOccIndex [protected] |
Definition at line 266 of file OccGridMapBase.h.
int hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::currUpdateIndex [protected] |
Definition at line 265 of file OccGridMapBase.h.