Namespaces |
| namespace | GFSReader |
Classes |
| class | Array2D |
| class | autoptr |
| class | CarmenConfiguration |
| class | Configuration |
| struct | Covariance3 |
| class | DataSmoother |
| class | DIncompatibleMatrixException |
| class | DMatrix |
| class | DNotInvertibleMatrixException |
| class | DNotSquareMatrixException |
| struct | EigenCovariance3 |
| class | FSRMovement |
| struct | Gaussian3 |
| 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 | RangeReading |
| class | RangeSensor |
| class | ScanMatcher |
| class | ScanMatcherProcessor |
| 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, Point > | PointPair |
typedef Map< PointAccumulator,
HierarchicalArray2D
< PointAccumulator > > | ScanMatcherMap |
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 > |
| point< T > | absoluteSum (const orientedpoint< T, A > &p1, const point< T > &p2) |
| template<class T , class A > |
| orientedpoint< T, A > | absoluteSum (const orientedpoint< T, A > &p1, const orientedpoint< T, A > &p2) |
| template<typename PointIterator > |
| Gaussian3 | computeGaussianFromSamples (PointIterator &pointBegin, PointIterator &pointEnd) |
| template<typename PointIterator , typename WeightIterator > |
| Gaussian3 | computeGaussianFromSamples (PointIterator &pointBegin, PointIterator &pointEnd, WeightIterator &weightBegin, WeightIterator &weightEnd) |
| template<class T , class A > |
| double | euclidianDist (const point< T > &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 orientedpoint< T, A > &p1, const orientedpoint< T, A > &p2) |
| template<class T > |
| double | euclidianDist (const point< T > &p1, const point< T > &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 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) |
| 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) |
| 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 , class A > |
| orientedpoint< T, A > | operator* (const T &v, const orientedpoint< T, A > &p) |
| template<class T , class A > |
| orientedpoint< T, A > | operator* (const orientedpoint< T, A > &p, const T &v) |
| template<class T > |
| T | operator* (const point< T > &p1, const point< T > &p2) |
| template<class T > |
| point< T > | operator* (const T &v, const point< T > &p) |
| template<class T > |
| point< T > | operator* (const point< T > &p, const T &v) |
| 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 T > |
| point< T > | operator- (const point< T > &p1, const point< T > &p2) |
| template<class X > |
| std::ostream & | operator<< (std::ostream &os, const DMatrix< X > &m) |
| void | printmemusage () |
| double | sampleGaussian (double sigma, unsigned long int S=0) |
| double | sampleUniformDouble (double min, double max) |
| int | sampleUniformInt (int max) |