Classes | Public Types | Public Member Functions | Static Public Member Functions | List of all members
PointMatcher< T > Struct Template Reference

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

#include <PointMatcher.h>

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

Public Member Functions

 PointMatcher ()
 Constructor, populates the registrars. More...
 

Static Public Member Functions

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

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 130 of file PointMatcher.h.

Member Typedef Documentation

◆ Array

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

A dense array over ScalarType.

Definition at line 175 of file PointMatcher.h.

◆ DataPointsFiltersConstIt

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

alias

Definition at line 463 of file PointMatcher.h.

◆ DataPointsFiltersIt

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

alias

Definition at line 462 of file PointMatcher.h.

◆ Int64Matrix

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

A dense signed 64-bits matrix.

Definition at line 173 of file PointMatcher.h.

◆ IntMatrix

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

A dense integer matrix.

Definition at line 171 of file PointMatcher.h.

◆ InvalidParameter

alias

Definition at line 189 of file PointMatcher.h.

◆ Matrix

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

A dense matrix over ScalarType.

Definition at line 169 of file PointMatcher.h.

◆ OutlierFiltersConstIt

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

alias

Definition at line 519 of file PointMatcher.h.

◆ OutlierFiltersIt

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

alias

Definition at line 520 of file PointMatcher.h.

◆ OutlierWeights

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 397 of file PointMatcher.h.

◆ ParameterDoc

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

alias

Definition at line 187 of file PointMatcher.h.

◆ Parameters

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

alias

Definition at line 186 of file PointMatcher.h.

◆ ParametersDoc

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

alias

Definition at line 188 of file PointMatcher.h.

◆ Parametrizable

alias

Definition at line 185 of file PointMatcher.h.

◆ Quaternion

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

A quaternion over ScalarType.

Definition at line 165 of file PointMatcher.h.

◆ QuaternionVector

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

A vector of quaternions over ScalarType.

Definition at line 167 of file PointMatcher.h.

◆ ScalarType

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

The scalar type.

Definition at line 159 of file PointMatcher.h.

◆ TransformationCheckersConstIt

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

alias

Definition at line 617 of file PointMatcher.h.

◆ TransformationCheckersIt

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

alias

Definition at line 616 of file PointMatcher.h.

◆ TransformationParameters

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 182 of file PointMatcher.h.

◆ TransformationsConstIt

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

alias

Definition at line 430 of file PointMatcher.h.

◆ TransformationsIt

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

alias

Definition at line 429 of file PointMatcher.h.

◆ Vector

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

A vector over ScalarType.

Definition at line 161 of file PointMatcher.h.

◆ VectorVector

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 163 of file PointMatcher.h.

Constructor & Destructor Documentation

◆ PointMatcher()

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

Constructor, populates the registrars.

Definition at line 61 of file Registry.cpp.

Member Function Documentation

◆ get()

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

Return instances.

Definition at line 145 of file Registry.cpp.

◆ swapDataPoints()

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 1023 of file pointmatcher/DataPoints.cpp.


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


libpointmatcher
Author(s):
autogenerated on Sat May 27 2023 02:38:04