Public Member Functions | Protected Attributes | List of all members
hectorslam::HectorSlamProcessor Class Reference

#include <HectorSlamProcessor.h>

Public Member Functions

void addMapMutex (int i, MapLockerInterface *mapMutex)
 
const GridMapgetGridMap (int mapLevel=0) const
 
const Eigen::Matrix3f & getLastScanMatchCovariance () const
 
const Eigen::Vector3f & getLastScanMatchPose () const
 
int getMapLevels () const
 
MapLockerInterfacegetMapMutex (int i)
 
float getScaleToMap () const
 
 HectorSlamProcessor (float mapResolution, int mapSizeX, int mapSizeY, const Eigen::Vector2f &startCoords, int multi_res_size, DrawInterface *drawInterfaceIn=0, HectorDebugInfoInterface *debugInterfaceIn=0)
 
void reset ()
 
void setMapUpdateMinAngleDiff (float angleChange)
 
void setMapUpdateMinDistDiff (float minDist)
 
void setUpdateFactorFree (float free_factor)
 
void setUpdateFactorOccupied (float occupied_factor)
 
void update (const DataContainer &dataContainer, const Eigen::Vector3f &poseHintWorld, bool map_without_matching=false)
 
 ~HectorSlamProcessor ()
 

Protected Attributes

HectorDebugInfoInterfacedebugInterface
 
DrawInterfacedrawInterface
 
Eigen::Vector3f lastMapUpdatePose
 
Eigen::Matrix3f lastScanMatchCov
 
Eigen::Vector3f lastScanMatchPose
 
MapRepresentationInterfacemapRep
 
float paramMinAngleDiffForMapUpdate
 
float paramMinDistanceDiffForMapUpdate
 

Detailed Description

Definition at line 50 of file HectorSlamProcessor.h.

Constructor & Destructor Documentation

◆ HectorSlamProcessor()

hectorslam::HectorSlamProcessor::HectorSlamProcessor ( float  mapResolution,
int  mapSizeX,
int  mapSizeY,
const Eigen::Vector2f &  startCoords,
int  multi_res_size,
DrawInterface drawInterfaceIn = 0,
HectorDebugInfoInterface debugInterfaceIn = 0 
)
inline

Definition at line 54 of file HectorSlamProcessor.h.

◆ ~HectorSlamProcessor()

hectorslam::HectorSlamProcessor::~HectorSlamProcessor ( )
inline

Definition at line 66 of file HectorSlamProcessor.h.

Member Function Documentation

◆ addMapMutex()

void hectorslam::HectorSlamProcessor::addMapMutex ( int  i,
MapLockerInterface mapMutex 
)
inline

Definition at line 133 of file HectorSlamProcessor.h.

◆ getGridMap()

const GridMap& hectorslam::HectorSlamProcessor::getGridMap ( int  mapLevel = 0) const
inline

Definition at line 131 of file HectorSlamProcessor.h.

◆ getLastScanMatchCovariance()

const Eigen::Matrix3f& hectorslam::HectorSlamProcessor::getLastScanMatchCovariance ( ) const
inline

Definition at line 127 of file HectorSlamProcessor.h.

◆ getLastScanMatchPose()

const Eigen::Vector3f& hectorslam::HectorSlamProcessor::getLastScanMatchPose ( ) const
inline

Definition at line 126 of file HectorSlamProcessor.h.

◆ getMapLevels()

int hectorslam::HectorSlamProcessor::getMapLevels ( ) const
inline

Definition at line 130 of file HectorSlamProcessor.h.

◆ getMapMutex()

MapLockerInterface* hectorslam::HectorSlamProcessor::getMapMutex ( int  i)
inline

Definition at line 134 of file HectorSlamProcessor.h.

◆ getScaleToMap()

float hectorslam::HectorSlamProcessor::getScaleToMap ( ) const
inline

Definition at line 128 of file HectorSlamProcessor.h.

◆ reset()

void hectorslam::HectorSlamProcessor::reset ( )
inline

Definition at line 115 of file HectorSlamProcessor.h.

◆ setMapUpdateMinAngleDiff()

void hectorslam::HectorSlamProcessor::setMapUpdateMinAngleDiff ( float  angleChange)
inline

Definition at line 139 of file HectorSlamProcessor.h.

◆ setMapUpdateMinDistDiff()

void hectorslam::HectorSlamProcessor::setMapUpdateMinDistDiff ( float  minDist)
inline

Definition at line 138 of file HectorSlamProcessor.h.

◆ setUpdateFactorFree()

void hectorslam::HectorSlamProcessor::setUpdateFactorFree ( float  free_factor)
inline

Definition at line 136 of file HectorSlamProcessor.h.

◆ setUpdateFactorOccupied()

void hectorslam::HectorSlamProcessor::setUpdateFactorOccupied ( float  occupied_factor)
inline

Definition at line 137 of file HectorSlamProcessor.h.

◆ update()

void hectorslam::HectorSlamProcessor::update ( const DataContainer dataContainer,
const Eigen::Vector3f &  poseHintWorld,
bool  map_without_matching = false 
)
inline

Definition at line 71 of file HectorSlamProcessor.h.

Member Data Documentation

◆ debugInterface

HectorDebugInfoInterface* hectorslam::HectorSlamProcessor::debugInterface
protected

Definition at line 153 of file HectorSlamProcessor.h.

◆ drawInterface

DrawInterface* hectorslam::HectorSlamProcessor::drawInterface
protected

Definition at line 152 of file HectorSlamProcessor.h.

◆ lastMapUpdatePose

Eigen::Vector3f hectorslam::HectorSlamProcessor::lastMapUpdatePose
protected

Definition at line 145 of file HectorSlamProcessor.h.

◆ lastScanMatchCov

Eigen::Matrix3f hectorslam::HectorSlamProcessor::lastScanMatchCov
protected

Definition at line 147 of file HectorSlamProcessor.h.

◆ lastScanMatchPose

Eigen::Vector3f hectorslam::HectorSlamProcessor::lastScanMatchPose
protected

Definition at line 146 of file HectorSlamProcessor.h.

◆ mapRep

MapRepresentationInterface* hectorslam::HectorSlamProcessor::mapRep
protected

Definition at line 139 of file HectorSlamProcessor.h.

◆ paramMinAngleDiffForMapUpdate

float hectorslam::HectorSlamProcessor::paramMinAngleDiffForMapUpdate
protected

Definition at line 150 of file HectorSlamProcessor.h.

◆ paramMinDistanceDiffForMapUpdate

float hectorslam::HectorSlamProcessor::paramMinDistanceDiffForMapUpdate
protected

Definition at line 149 of file HectorSlamProcessor.h.


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


hector_mapping
Author(s): Stefan Kohlbrecher
autogenerated on Sat Mar 12 2022 03:57:50