GMapping::ScanMatcher Class Reference

#include <scanmatcher.h>

List of all members.

Public Types

typedef Covariance3 CovarianceMatrix

Public Member Functions

void computeActiveArea (ScanMatcherMap &map, const OrientedPoint &p, const double *readings)
double icpOptimize (OrientedPoint &pnew, const ScanMatcherMap &map, const OrientedPoint &p, const double *readings) const
double icpStep (OrientedPoint &pret, const ScanMatcherMap &map, const OrientedPoint &p, const double *readings) const
void invalidateActiveArea ()
const double * laserAngles () const
unsigned int laserBeams () const
double likelihood (double &_lmax, OrientedPoint &_mean, CovarianceMatrix &_cov, const ScanMatcherMap &map, const OrientedPoint &p, Gaussian3 &odometry, const double *readings, double gain=180.)
double likelihood (double &lmax, OrientedPoint &mean, CovarianceMatrix &cov, const ScanMatcherMap &map, const OrientedPoint &p, const double *readings)
unsigned int likelihoodAndScore (double &s, double &l, const ScanMatcherMap &map, const OrientedPoint &p, const double *readings) const
double optimize (OrientedPoint &mean, CovarianceMatrix &cov, const ScanMatcherMap &map, const OrientedPoint &p, const double *readings) const
double optimize (OrientedPoint &pnew, const ScanMatcherMap &map, const OrientedPoint &p, const double *readings) const
double registerScan (ScanMatcherMap &map, const OrientedPoint &p, const double *readings)
 ScanMatcher ()
double score (const ScanMatcherMap &map, const OrientedPoint &p, const double *readings) const
void setLaserParameters (unsigned int beams, double *angles, const OrientedPoint &lpose)
void setMatchingParameters (double urange, double range, double sigma, int kernsize, double lopt, double aopt, int iterations, double likelihoodSigma=1, unsigned int likelihoodSkip=0)
 ~ScanMatcher ()

Static Public Attributes

static const double nullLikelihood

Protected Attributes

bool m_activeAreaComputed
double m_laserAngles [LASER_MAXBEAMS]
unsigned int m_laserBeams
IntPointm_linePoints

Detailed Description

Definition at line 14 of file scanmatcher.h.


Member Typedef Documentation

Definition at line 16 of file scanmatcher.h.


Constructor & Destructor Documentation

GMapping::ScanMatcher::ScanMatcher (  ) 
GMapping::ScanMatcher::~ScanMatcher (  ) 

Member Function Documentation

void GMapping::ScanMatcher::computeActiveArea ( ScanMatcherMap map,
const OrientedPoint p,
const double *  readings 
)
double GMapping::ScanMatcher::icpOptimize ( OrientedPoint pnew,
const ScanMatcherMap map,
const OrientedPoint p,
const double *  readings 
) const
double GMapping::ScanMatcher::icpStep ( OrientedPoint pret,
const ScanMatcherMap map,
const OrientedPoint p,
const double *  readings 
) const [inline]

Definition at line 77 of file scanmatcher.h.

void GMapping::ScanMatcher::invalidateActiveArea (  ) 
const double* GMapping::ScanMatcher::laserAngles (  )  const [inline]

Definition at line 37 of file scanmatcher.h.

unsigned int GMapping::ScanMatcher::laserBeams (  )  const [inline]

Definition at line 38 of file scanmatcher.h.

double GMapping::ScanMatcher::likelihood ( double &  _lmax,
OrientedPoint _mean,
CovarianceMatrix _cov,
const ScanMatcherMap map,
const OrientedPoint p,
Gaussian3 odometry,
const double *  readings,
double  gain = 180. 
)
double GMapping::ScanMatcher::likelihood ( double &  lmax,
OrientedPoint mean,
CovarianceMatrix cov,
const ScanMatcherMap map,
const OrientedPoint p,
const double *  readings 
)
unsigned int GMapping::ScanMatcher::likelihoodAndScore ( double &  s,
double &  l,
const ScanMatcherMap map,
const OrientedPoint p,
const double *  readings 
) const [inline]

Definition at line 191 of file scanmatcher.h.

double GMapping::ScanMatcher::optimize ( OrientedPoint mean,
CovarianceMatrix cov,
const ScanMatcherMap map,
const OrientedPoint p,
const double *  readings 
) const
double GMapping::ScanMatcher::optimize ( OrientedPoint pnew,
const ScanMatcherMap map,
const OrientedPoint p,
const double *  readings 
) const
double GMapping::ScanMatcher::registerScan ( ScanMatcherMap map,
const OrientedPoint p,
const double *  readings 
)
double GMapping::ScanMatcher::score ( const ScanMatcherMap map,
const OrientedPoint p,
const double *  readings 
) const [inline]

Definition at line 143 of file scanmatcher.h.

void GMapping::ScanMatcher::setLaserParameters ( unsigned int  beams,
double *  angles,
const OrientedPoint lpose 
)
void GMapping::ScanMatcher::setMatchingParameters ( double  urange,
double  range,
double  sigma,
int  kernsize,
double  lopt,
double  aopt,
int  iterations,
double  likelihoodSigma = 1,
unsigned int  likelihoodSkip = 0 
)

Member Data Documentation

Definition at line 43 of file scanmatcher.h.

double GMapping::ScanMatcher::m_laserAngles[LASER_MAXBEAMS] [protected]

Definition at line 47 of file scanmatcher.h.

unsigned int GMapping::ScanMatcher::m_laserBeams [protected]

laser parameters

Definition at line 46 of file scanmatcher.h.

scan_matcher parameters

Definition at line 74 of file scanmatcher.h.

Definition at line 40 of file scanmatcher.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


gmapping
Author(s): Giorgio Grisetti, Cyrill Stachniss, Wolfram Burgard; ROS wrapper by Brian Gerkey
autogenerated on Fri Jan 11 09:32:13 2013