Classes | Public Types | Public Member Functions | Static Public Member Functions
PointMatcher< T > Struct Template Reference

Functions and classes that are dependant on scalar type are defined in this templatized class. More...

#include <PointMatcher.h>

List of all members.

Classes

struct  ConvergenceError
 Point matcher did not converge. More...
struct  DataPoints
 A point cloud. More...
struct  DataPointsFilter
 A data filter takes a point cloud as input, transforms it, and produces another point cloud as output. More...
struct  DataPointsFilters
 A chain of DataPointsFilter. More...
struct  ErrorMinimizer
 An error minimizer will compute a transformation matrix such as to minimize the error between the reading and the reference. More...
struct  ICP
 ICP algorithm. More...
struct  ICPChainBase
 Stuff common to all ICP algorithms. More...
struct  ICPSequence
 ICP alogrithm, taking a sequence of clouds and using a map. More...
struct  Inspector
 An inspector allows to log data at the different steps, for analysis. More...
struct  Matcher
 A matcher links points in the reading to points in the reference. More...
struct  Matches
 Result of the data-association step (Matcher::findClosests), before outlier rejection. More...
struct  OutlierFilter
 An outlier filter removes or weights links between points in reading and their matched points in reference, depending on some criteria. More...
struct  OutlierFilters
 A chain of OutlierFilter. More...
struct  Transformation
 A function that transforms points and their descriptors given a transformation matrix. More...
struct  TransformationChecker
 A transformation checker can stop the iteration depending on some conditions. More...
struct  TransformationCheckers
 A chain of TransformationChecker. More...
struct  Transformations
 A chain of Transformation. More...

Public Types

typedef
DataPointsFilters::const_iterator 
DataPointsFiltersConstIt
 alias
typedef DataPointsFilters::iterator DataPointsFiltersIt
 alias
typedef Eigen::Matrix< int,
Eigen::Dynamic, Eigen::Dynamic > 
IntMatrix
 A dense integer matrix.
typedef
Parametrizable::InvalidParameter 
InvalidParameter
 alias
typedef Eigen::Matrix< T,
Eigen::Dynamic, Eigen::Dynamic > 
Matrix
 A dense matrix over ScalarType.
typedef
OutlierFilters::const_iterator 
OutlierFiltersConstIt
 alias
typedef OutlierFilters::iterator OutlierFiltersIt
 alias
typedef Matrix OutlierWeights
 Weights of the associations between the points in Matches and the points in the reference.
typedef
Parametrizable::ParameterDoc 
ParameterDoc
 alias
typedef Parametrizable::Parameters Parameters
 alias
typedef
Parametrizable::ParametersDoc 
ParametersDoc
 alias
typedef
PointMatcherSupport::Parametrizable 
Parametrizable
 alias
typedef Eigen::Quaternion< T > Quaternion
 A quaternion over ScalarType.
typedef std::vector
< Quaternion,
Eigen::aligned_allocator
< Quaternion > > 
QuaternionVector
 A vector of quaternions over ScalarType.
typedef T ScalarType
 The scalar type.
typedef
TransformationCheckers::const_iterator 
TransformationCheckersConstIt
 alias
typedef
TransformationCheckers::iterator 
TransformationCheckersIt
 alias
typedef Matrix TransformationParameters
 A matrix holding the parameters a transformation.
typedef
Transformations::const_iterator 
TransformationsConstIt
 alias
typedef Transformations::iterator TransformationsIt
 alias
typedef Eigen::Matrix< T,
Eigen::Dynamic, 1 > 
Vector
 A vector over ScalarType.
typedef std::vector< Vector,
Eigen::aligned_allocator
< Vector > > 
VectorVector
 A vector of vector over ScalarType, not a matrix.

Public Member Functions

 PointMatcher ()
 Constructor, populates the registrars.

Static Public Member Functions

static const PointMatcherget ()
 Return instances.
static void swapDataPoints (DataPoints &a, DataPoints &b)
 Exchange in place point clouds a and b, with no data copy.

Detailed Description

template<typename T>
struct PointMatcher< T >

Functions and classes that are dependant on scalar type are defined in this templatized class.

Definition at line 129 of file PointMatcher.h.


Member Typedef Documentation

template<typename T>
typedef DataPointsFilters::const_iterator PointMatcher< T >::DataPointsFiltersConstIt

alias

Definition at line 382 of file PointMatcher.h.

template<typename T>
typedef DataPointsFilters::iterator PointMatcher< T >::DataPointsFiltersIt

alias

Definition at line 381 of file PointMatcher.h.

template<typename T>
typedef Eigen::Matrix<int, Eigen::Dynamic, Eigen::Dynamic> PointMatcher< T >::IntMatrix

A dense integer matrix.

Definition at line 170 of file PointMatcher.h.

alias

Definition at line 183 of file PointMatcher.h.

template<typename T>
typedef Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> PointMatcher< T >::Matrix

A dense matrix over ScalarType.

Definition at line 168 of file PointMatcher.h.

template<typename T>
typedef OutlierFilters::const_iterator PointMatcher< T >::OutlierFiltersConstIt

alias

Definition at line 438 of file PointMatcher.h.

template<typename T>
typedef OutlierFilters::iterator PointMatcher< T >::OutlierFiltersIt

alias

Definition at line 439 of file PointMatcher.h.

template<typename T>
typedef Matrix PointMatcher< T >::OutlierWeights

Weights of the associations between the points in Matches and the points in the reference.

A weight of 0 means no association, while a weight of 1 means a complete trust in association.

Definition at line 322 of file PointMatcher.h.

template<typename T>
typedef Parametrizable::ParameterDoc PointMatcher< T >::ParameterDoc

alias

Definition at line 181 of file PointMatcher.h.

template<typename T>
typedef Parametrizable::Parameters PointMatcher< T >::Parameters

alias

Definition at line 180 of file PointMatcher.h.

template<typename T>
typedef Parametrizable::ParametersDoc PointMatcher< T >::ParametersDoc

alias

Definition at line 182 of file PointMatcher.h.

alias

Definition at line 179 of file PointMatcher.h.

template<typename T>
typedef Eigen::Quaternion<T> PointMatcher< T >::Quaternion

A quaternion over ScalarType.

Definition at line 164 of file PointMatcher.h.

template<typename T>
typedef std::vector<Quaternion, Eigen::aligned_allocator<Quaternion> > PointMatcher< T >::QuaternionVector

A vector of quaternions over ScalarType.

Definition at line 166 of file PointMatcher.h.

template<typename T>
typedef T PointMatcher< T >::ScalarType

The scalar type.

Definition at line 158 of file PointMatcher.h.

template<typename T>
typedef TransformationCheckers::const_iterator PointMatcher< T >::TransformationCheckersConstIt

alias

Definition at line 528 of file PointMatcher.h.

template<typename T>
typedef TransformationCheckers::iterator PointMatcher< T >::TransformationCheckersIt

alias

Definition at line 527 of file PointMatcher.h.

template<typename T>
typedef Matrix PointMatcher< T >::TransformationParameters

A matrix holding the parameters a transformation.

The transformation lies in the special Euclidean group of dimension $n$, $SE(n)$, implemented as a dense matrix of size $n+1 \times n+1$ over ScalarType.

Definition at line 176 of file PointMatcher.h.

template<typename T>
typedef Transformations::const_iterator PointMatcher< T >::TransformationsConstIt

alias

Definition at line 352 of file PointMatcher.h.

template<typename T>
typedef Transformations::iterator PointMatcher< T >::TransformationsIt

alias

Definition at line 351 of file PointMatcher.h.

template<typename T>
typedef Eigen::Matrix<T, Eigen::Dynamic, 1> PointMatcher< T >::Vector

A vector over ScalarType.

Definition at line 160 of file PointMatcher.h.

template<typename T>
typedef std::vector<Vector, Eigen::aligned_allocator<Vector> > PointMatcher< T >::VectorVector

A vector of vector over ScalarType, not a matrix.

Definition at line 162 of file PointMatcher.h.


Constructor & Destructor Documentation

template<typename T >
PointMatcher< T >::PointMatcher ( )

Constructor, populates the registrars.

Definition at line 61 of file Registry.cpp.


Member Function Documentation

template<typename T >
template const PointMatcher< double > & PointMatcher< T >::get ( ) [static]

Return instances.

Definition at line 125 of file Registry.cpp.

template<typename T >
template void PointMatcher< T >::swapDataPoints ( DataPoints a,
DataPoints b 
) [static]

Exchange in place point clouds a and b, with no data copy.

Definition at line 707 of file DataPoints.cpp.


The documentation for this struct was generated from the following files:


libpointmatcher
Author(s): Stéphane Magnenat, François Pomerleau
autogenerated on Thu Jan 2 2014 11:16:06