Public Member Functions | Protected Attributes | List of all members
hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions > Class Template Reference

#include <OccGridMapBase.h>

Inheritance diagram for hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >:
Inheritance graph
[legend]

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 ()
 
- Public Member Functions inherited from hectorslam::GridMapBase< ConcreteCellType >
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 MapDimensionPropertiesgetMapDimProperties () 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
 
GridMapBaseoperator= (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 ()
 

Protected Attributes

ConcreteGridFunctions concreteGridFunctions
 
int currMarkFreeIndex
 
int currMarkOccIndex
 
int currUpdateIndex
 
- Protected Attributes inherited from hectorslam::GridMapBase< ConcreteCellType >
ConcreteCellType * mapArray
 Map representation used with plain pointer array. More...
 
MapDimensionProperties mapDimensionProperties
 
Eigen::Affine2f mapTworld
 Homogenous 2D transform from world to map coordinates. More...
 
float scaleToMap
 Scaling factor from world to map. More...
 
int sizeX
 
Eigen::Affine2f worldTmap
 Homogenous 2D transform from map to world coordinates. More...
 
Eigen::Affine3f worldTmap3D
 Homogenous 3D transform from map to world coordinates. More...
 

Detailed Description

template<typename ConcreteCellType, typename ConcreteGridFunctions>
class hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >

Definition at line 42 of file OccGridMapBase.h.

Constructor & Destructor Documentation

template<typename ConcreteCellType , typename ConcreteGridFunctions >
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.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
virtual hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::~OccGridMapBase ( )
inlinevirtual

Definition at line 57 of file OccGridMapBase.h.

Member Function Documentation

template<typename ConcreteCellType , typename ConcreteGridFunctions >
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.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::bresenhamCellFree ( unsigned int  offset)
inline

Definition at line 216 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::bresenhamCellOcc ( unsigned int  offset)
inline

Definition at line 226 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
float hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::getGridProbabilityMap ( int  index) const
inline

Definition at line 74 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
float hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::getObstacleThreshold ( ) const
inline

Definition at line 99 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
bool hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::isFree ( int  xMap,
int  yMap 
) const
inline

Definition at line 84 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
bool hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::isFree ( int  index) const
inline

Definition at line 94 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
bool hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::isOccupied ( int  xMap,
int  yMap 
) const
inline

Definition at line 79 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
bool hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::isOccupied ( int  index) const
inline

Definition at line 89 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::setUpdateFreeFactor ( float  factor)
inline

Definition at line 106 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::setUpdateOccupiedFactor ( float  factor)
inline

Definition at line 111 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
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

Parameters
dataContainerContains the laser scan data
robotPoseWorldThe 2D robot pose in world coordinates

Definition at line 121 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
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.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::updateSetFree ( int  index)
inline

Definition at line 64 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::updateSetOccupied ( int  index)
inline

Definition at line 59 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
void hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::updateUnsetFree ( int  index)
inline

Definition at line 69 of file OccGridMapBase.h.

Member Data Documentation

template<typename ConcreteCellType , typename ConcreteGridFunctions >
ConcreteGridFunctions hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::concreteGridFunctions
protected

Definition at line 264 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
int hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::currMarkFreeIndex
protected

Definition at line 267 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
int hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::currMarkOccIndex
protected

Definition at line 266 of file OccGridMapBase.h.

template<typename ConcreteCellType , typename ConcreteGridFunctions >
int hectorslam::OccGridMapBase< ConcreteCellType, ConcreteGridFunctions >::currUpdateIndex
protected

Definition at line 265 of file OccGridMapBase.h.


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


hector_mapping
Author(s): Stefan Kohlbrecher
autogenerated on Sun Nov 3 2019 03:18:33