Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
GMapping Namespace Reference

Namespaces

namespace  GFSReader

Classes

class  Array2D
class  autoptr
class  CarmenConfiguration
class  CarmenWrapper
class  Configuration
struct  Covariance3
class  DataSmoother
class  DIncompatibleMatrixException
class  DMatrix
class  DNotInvertibleMatrixException
class  DNotSquareMatrixException
struct  EigenCovariance3
class  FSRMovement
struct  Gaussian3
struct  GraphMapEdge
struct  GraphMapPatch
struct  GraphPatchDirectoryCell
struct  GraphPatchGraph
struct  GridLineTraversal
struct  GridLineTraversalLine
class  GridSlamProcessor
class  HierarchicalArray2D
class  InputSensorStream
class  LogSensorStream
class  LuMilesProcessor
class  Map
struct  MotionModel
class  OdometryReading
class  OdometrySensor
struct  Optimizer
struct  OptimizerParams
class  OrientedBoundingBox
struct  orientedpoint
struct  point
struct  PointAccumulator
struct  pointcomparator
struct  pointradialcomparator
class  QParticleViewer
class  RangeReading
class  RangeSensor
class  ScanMatcher
class  ScanMatcherProcessor
struct  ScoredMove
class  Sensor
class  SensorLog
class  SensorReading
class  SensorStream

Typedefs

typedef Array2D< double > DoubleArray2D
typedef Map< double,
DoubleArray2D, false > 
DoubleMap
typedef point< int > IntPoint
typedef orientedpoint< double,
double > 
OrientedPoint
typedef point< double > Point
typedef std::pair< Point, PointPointPair
typedef Map< PointAccumulator,
HierarchicalArray2D
< PointAccumulator > > 
ScanMatcherMap
typedef std::list< ScoredMoveScoredMoveList
typedef std::map< std::string,
Sensor * > 
SensorMap
typedef std::multimap< const
GridSlamProcessor::TNode
*, GridSlamProcessor::TNode * > 
TNodeMultimap

Enumerations

enum  AccessibilityState { Outside = 0x0, Inside = 0x1, Allocated = 0x2 }

Functions

template<class T , class A >
orientedpoint< T, A > absoluteDifference (const orientedpoint< T, A > &p1, const orientedpoint< T, A > &p2)
template<class T , class A >
orientedpoint< T, A > absoluteSum (const orientedpoint< T, A > &p1, const orientedpoint< T, A > &p2)
template<class T , class A >
point< T > absoluteSum (const orientedpoint< T, A > &p1, const point< T > &p2)
template<typename PointIterator , typename WeightIterator >
Gaussian3 computeGaussianFromSamples (PointIterator &pointBegin, PointIterator &pointEnd, WeightIterator &weightBegin, WeightIterator &weightEnd)
template<typename PointIterator >
Gaussian3 computeGaussianFromSamples (PointIterator &pointBegin, PointIterator &pointEnd)
template<class T >
double euclidianDist (const point< T > &p1, const point< T > &p2)
template<class T , class A >
double euclidianDist (const orientedpoint< T, A > &p1, const orientedpoint< T, A > &p2)
template<class T , class A >
double euclidianDist (const orientedpoint< T, A > &p1, const point< T > &p2)
template<class T , class A >
double euclidianDist (const point< T > &p1, const orientedpoint< T, A > &p2)
double evalGaussian (double sigmaSquare, double delta)
double evalLogGaussian (double sigmaSquare, double delta)
template<typename PointPairContainer >
double icpNonlinearStep (OrientedPoint &retval, const PointPairContainer &container)
template<typename PointPairContainer >
double icpStep (OrientedPoint &retval, const PointPairContainer &container)
template<class T , class F >
point< T > interpolate (const point< T > &p1, const F &t1, const point< T > &p2, const F &t2, const F &t3)
template<class T , class A , class F >
orientedpoint< T, A > interpolate (const orientedpoint< T, A > &p1, const F &t1, const orientedpoint< T, A > &p2, const F &t2, const F &t3)
int main (int argc, conat char **argv)
template<class T >
point< T > max (const point< T > &p1, const point< T > &p2)
template<class T >
point< T > min (const point< T > &p1, const point< T > &p2)
template<class T >
point< T > operator* (const point< T > &p, const T &v)
template<class T >
point< T > operator* (const T &v, const point< T > &p)
template<class T >
operator* (const point< T > &p1, const point< T > &p2)
template<class T , class A >
orientedpoint< T, A > operator* (const orientedpoint< T, A > &p, const T &v)
template<class T , class A >
orientedpoint< T, A > operator* (const T &v, const orientedpoint< T, A > &p)
template<class T >
point< T > operator+ (const point< T > &p1, const point< T > &p2)
template<class T , class A >
orientedpoint< T, A > operator+ (const orientedpoint< T, A > &p1, const orientedpoint< T, A > &p2)
template<class T >
point< T > operator- (const point< T > &p1, const point< T > &p2)
template<class T , class A >
orientedpoint< T, A > operator- (const orientedpoint< T, A > &p1, const orientedpoint< T, A > &p2)
template<class X >
std::ostream & operator<< (std::ostream &os, const DMatrix< X > &m)
double pf_ran_gaussian (double sigma)
void printmemusage ()
double propagateWeight (GridSlamProcessor::TNode *n, double weight)
double sampleGaussian (double sigma, unsigned int S=0)
double sampleUniformDouble (double min, double max)
int sampleUniformInt (int max)

Variables

const double m_distanceThresholdCheck = 20
typedef Map< GraphPatchDirectoryCell >

Typedef Documentation

The cells have to define the special value Cell::Unknown to handle with the unallocated areas. The cells have to define (int) constructor;

Definition at line 13 of file map.h.

typedef Map<double, DoubleArray2D, false> GMapping::DoubleMap

Definition at line 95 of file map.h.

typedef point<int> GMapping::IntPoint

Definition at line 201 of file point.h.

typedef orientedpoint<double, double> GMapping::OrientedPoint

Definition at line 203 of file point.h.

typedef point<double> GMapping::Point

Definition at line 202 of file point.h.

typedef std::pair<Point,Point> GMapping::PointPair

Definition at line 10 of file icp.h.

Definition at line 50 of file smmap.h.

typedef std::list< ScoredMove > GMapping::ScoredMoveList

Definition at line 428 of file scanmatcher.cpp.

typedef std::map<std::string, Sensor*> GMapping::SensorMap

Definition at line 19 of file sensor.h.

Definition at line 330 of file gridslamprocessor.h.


Enumeration Type Documentation

Enumerator:
Outside 
Inside 
Allocated 

Definition at line 5 of file accessstate.h.


Function Documentation

template<class T , class A >
orientedpoint<T,A> GMapping::absoluteDifference ( const orientedpoint< T, A > &  p1,
const orientedpoint< T, A > &  p2 
)

Definition at line 107 of file point.h.

template<class T , class A >
orientedpoint<T,A> GMapping::absoluteSum ( const orientedpoint< T, A > &  p1,
const orientedpoint< T, A > &  p2 
)

Definition at line 116 of file point.h.

template<class T , class A >
point<T> GMapping::absoluteSum ( const orientedpoint< T, A > &  p1,
const point< T > &  p2 
)

Definition at line 123 of file point.h.

template<typename PointIterator , typename WeightIterator >
Gaussian3 GMapping::computeGaussianFromSamples ( PointIterator &  pointBegin,
PointIterator &  pointEnd,
WeightIterator &  weightBegin,
WeightIterator &  weightEnd 
)

Definition at line 43 of file stat.h.

template<typename PointIterator >
Gaussian3 GMapping::computeGaussianFromSamples ( PointIterator &  pointBegin,
PointIterator &  pointEnd 
)

Definition at line 98 of file stat.h.

template<class T >
double GMapping::euclidianDist ( const point< T > &  p1,
const point< T > &  p2 
) [inline]

Definition at line 183 of file point.h.

template<class T , class A >
double GMapping::euclidianDist ( const orientedpoint< T, A > &  p1,
const orientedpoint< T, A > &  p2 
) [inline]

Definition at line 187 of file point.h.

template<class T , class A >
double GMapping::euclidianDist ( const orientedpoint< T, A > &  p1,
const point< T > &  p2 
) [inline]

Definition at line 191 of file point.h.

template<class T , class A >
double GMapping::euclidianDist ( const point< T > &  p1,
const orientedpoint< T, A > &  p2 
) [inline]

Definition at line 195 of file point.h.

double GMapping::evalGaussian ( double  sigmaSquare,
double  delta 
)
double GMapping::evalLogGaussian ( double  sigmaSquare,
double  delta 
)

Definition at line 75 of file stat.cpp.

template<typename PointPairContainer >
double GMapping::icpNonlinearStep ( OrientedPoint &  retval,
const PointPairContainer &  container 
)

Definition at line 48 of file icp.h.

template<typename PointPairContainer >
double GMapping::icpStep ( OrientedPoint &  retval,
const PointPairContainer &  container 
)

Definition at line 13 of file icp.h.

template<class T , class F >
point<T> GMapping::interpolate ( const point< T > &  p1,
const F &  t1,
const point< T > &  p2,
const F &  t2,
const F &  t3 
) [inline]

Definition at line 162 of file point.h.

template<class T , class A , class F >
orientedpoint<T,A> GMapping::interpolate ( const orientedpoint< T, A > &  p1,
const F &  t1,
const orientedpoint< T, A > &  p2,
const F &  t2,
const F &  t3 
) [inline]

Definition at line 170 of file point.h.

int GMapping::main ( int  argc,
conat char **  argv 
)

Definition at line 45 of file lumiles.h.

template<class T >
point<T> GMapping::max ( const point< T > &  p1,
const point< T > &  p2 
) [inline]

Definition at line 146 of file point.h.

template<class T >
point<T> GMapping::min ( const point< T > &  p1,
const point< T > &  p2 
) [inline]

Definition at line 154 of file point.h.

template<class T >
point<T> GMapping::operator* ( const point< T > &  p,
const T &  v 
) [inline]

Definition at line 30 of file point.h.

template<class T >
point<T> GMapping::operator* ( const T &  v,
const point< T > &  p 
) [inline]

Definition at line 35 of file point.h.

template<class T >
T GMapping::operator* ( const point< T > &  p1,
const point< T > &  p2 
) [inline]

Definition at line 40 of file point.h.

template<class T , class A >
orientedpoint<T,A> GMapping::operator* ( const orientedpoint< T, A > &  p,
const T &  v 
)

Definition at line 97 of file point.h.

template<class T , class A >
orientedpoint<T,A> GMapping::operator* ( const T &  v,
const orientedpoint< T, A > &  p 
)

Definition at line 102 of file point.h.

template<class T >
point<T> GMapping::operator+ ( const point< T > &  p1,
const point< T > &  p2 
) [inline]

Definition at line 20 of file point.h.

template<class T , class A >
orientedpoint<T,A> GMapping::operator+ ( const orientedpoint< T, A > &  p1,
const orientedpoint< T, A > &  p2 
)

Definition at line 87 of file point.h.

template<class T >
point<T> GMapping::operator- ( const point< T > &  p1,
const point< T > &  p2 
) [inline]

Definition at line 25 of file point.h.

template<class T , class A >
orientedpoint<T,A> GMapping::operator- ( const orientedpoint< T, A > &  p1,
const orientedpoint< T, A > &  p2 
)

Definition at line 92 of file point.h.

template<class X >
std::ostream& GMapping::operator<< ( std::ostream &  os,
const DMatrix< X > &  m 
)

Definition at line 217 of file dmatrix.h.

double GMapping::pf_ran_gaussian ( double  sigma)

Definition at line 31 of file stat.cpp.

Definition at line 6 of file printmemusage.cpp.

double GMapping::propagateWeight ( GridSlamProcessor::TNode *  n,
double  weight 
)

Definition at line 220 of file gridslamprocessor_tree.cpp.

double GMapping::sampleGaussian ( double  sigma,
unsigned int  S = 0 
)

stupid utility function for drawing particles form a zero mean, sigma variance normal distribution probably it should not go there

Definition at line 48 of file stat.cpp.

double GMapping::sampleUniformDouble ( double  min,
double  max 
)
int GMapping::sampleUniformInt ( int  max)

Variable Documentation

Definition at line 16 of file gridslamprocessor.cpp.

Definition at line 55 of file graphmap.cpp.



openslam_gmapping
Author(s): Giorgio Grisetti, Cyrill Stachniss, Wolfram Burgard
autogenerated on Fri Aug 28 2015 11:56:21