Public Member Functions | Protected Attributes | List of all members
hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod > Class Template Reference

#include <OccGridMapUtil.h>

Public Member Functions

void getCompleteHessianDerivs (const Eigen::Vector3f &pose, const DataContainer &dataPoints, Eigen::Matrix3f &H, Eigen::Vector3f &dTr)
 
Eigen::Matrix3f getCovarianceForPose (const Eigen::Vector3f &mapPose, const DataContainer &dataPoints)
 
Eigen::Matrix3f getCovMatrixWorldCoords (const Eigen::Matrix3f &covMatMap)
 
float getLikelihoodForResidual (float residual, int numDataPoints)
 
float getLikelihoodForState (const Eigen::Vector3f &state, const DataContainer &dataPoints)
 
Eigen::Vector3f getMapCoordsPose (const Eigen::Vector3f &worldPose) const
 
float getResidualForState (const Eigen::Vector3f &state, const DataContainer &dataPoints)
 
const std::vector< Eigen::Vector3f > & getSamplePoints () const
 
Eigen::Affine2f getTransformForState (const Eigen::Vector3f &transVector) const
 
Eigen::Translation2f getTranslationForState (const Eigen::Vector3f &transVector) const
 
float getUnfilteredGridPoint (Eigen::Vector2i &gridCoords) const
 
float getUnfilteredGridPoint (int index) const
 
Eigen::Vector2f getWorldCoordsPoint (const Eigen::Vector2f &mapPoint) const
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3f getWorldCoordsPose (const Eigen::Vector3f &mapPose) const
 
float interpMapValue (const Eigen::Vector2f &coords)
 
Eigen::Vector3f interpMapValueWithDerivatives (const Eigen::Vector2f &coords)
 
 OccGridMapUtil (const ConcreteOccGridMap *gridMap)
 
void resetCachedData ()
 
void resetSamplePoints ()
 
 ~OccGridMapUtil ()
 

Protected Attributes

ConcreteCacheMethod cacheMethod
 
const ConcreteOccGridMap * concreteGridMap
 
Eigen::Vector4f intensities
 
float mapObstacleThreshold
 
std::vector< Eigen::Vector3f > samplePoints
 
int size
 

Detailed Description

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
class hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >

Definition at line 40 of file OccGridMapUtil.h.

Constructor & Destructor Documentation

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::OccGridMapUtil ( const ConcreteOccGridMap *  gridMap)
inline

Definition at line 44 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::~OccGridMapUtil ( )
inline

Definition at line 52 of file OccGridMapUtil.h.

Member Function Documentation

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
void hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getCompleteHessianDerivs ( const Eigen::Vector3f &  pose,
const DataContainer dataPoints,
Eigen::Matrix3f &  H,
Eigen::Vector3f &  dTr 
)
inline

Definition at line 64 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
Eigen::Matrix3f hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getCovarianceForPose ( const Eigen::Vector3f &  mapPose,
const DataContainer dataPoints 
)
inline

Definition at line 106 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
Eigen::Matrix3f hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getCovMatrixWorldCoords ( const Eigen::Matrix3f &  covMatMap)
inline

Definition at line 162 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
float hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getLikelihoodForResidual ( float  residual,
int  numDataPoints 
)
inline

Definition at line 196 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
float hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getLikelihoodForState ( const Eigen::Vector3f &  state,
const DataContainer dataPoints 
)
inline

Definition at line 189 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
Eigen::Vector3f hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getMapCoordsPose ( const Eigen::Vector3f &  worldPose) const
inline

Definition at line 60 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
float hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getResidualForState ( const Eigen::Vector3f &  state,
const DataContainer dataPoints 
)
inline

Definition at line 204 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
const std::vector<Eigen::Vector3f>& hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getSamplePoints ( ) const
inline

Definition at line 369 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
Eigen::Affine2f hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getTransformForState ( const Eigen::Vector3f &  transVector) const
inline

Definition at line 349 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
Eigen::Translation2f hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getTranslationForState ( const Eigen::Vector3f &  transVector) const
inline

Definition at line 354 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
float hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getUnfilteredGridPoint ( Eigen::Vector2i &  gridCoords) const
inline

Definition at line 223 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
float hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getUnfilteredGridPoint ( int  index) const
inline

Definition at line 228 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
Eigen::Vector2f hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getWorldCoordsPoint ( const Eigen::Vector2f &  mapPoint) const
inline

Definition at line 62 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3f hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::getWorldCoordsPose ( const Eigen::Vector3f &  mapPose) const
inline

Definition at line 59 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
float hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::interpMapValue ( const Eigen::Vector2f &  coords)
inline

Definition at line 233 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
Eigen::Vector3f hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::interpMapValueWithDerivatives ( const Eigen::Vector2f &  coords)
inline

Definition at line 287 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
void hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::resetCachedData ( )
inline

Definition at line 359 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
void hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::resetSamplePoints ( )
inline

Definition at line 364 of file OccGridMapUtil.h.

Member Data Documentation

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
ConcreteCacheMethod hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::cacheMethod
protected

Definition at line 378 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
const ConcreteOccGridMap* hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::concreteGridMap
protected

Definition at line 380 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
Eigen::Vector4f hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::intensities
protected

Definition at line 376 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
float hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::mapObstacleThreshold
protected

Definition at line 386 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
std::vector<Eigen::Vector3f> hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::samplePoints
protected

Definition at line 382 of file OccGridMapUtil.h.

template<typename ConcreteOccGridMap, typename ConcreteCacheMethod>
int hectorslam::OccGridMapUtil< ConcreteOccGridMap, ConcreteCacheMethod >::size
protected

Definition at line 384 of file OccGridMapUtil.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