36 #ifndef POINT_TO_PLANE_ERROR_MINIMIZER_H 37 #define POINT_TO_PLANE_ERROR_MINIMIZER_H 61 return "PointToPlaneErrorMinimizer";
66 return "Point-to-plane error (or point-to-line in 2D). Per \\cite{Chen1991Point2Plane}.";
72 {
"force2D",
"If set to true(1), the minimization will be forced to give a solution in 2D (i.e., on the XY-plane) even with 3D inputs.",
"0",
"0",
"1", &P::Comp<bool>},
73 {
"force4DOF",
"If set to true(1), the minimization will optimize only yaw and translation, pitch and roll will follow the prior.",
"0",
"0",
"1", &P::Comp<bool>}
84 virtual TransformationParameters
compute(
const ErrorElements& mPts);
86 virtual T getResidualError(
const DataPoints& filteredReading,
const DataPoints& filteredReference,
const OutlierWeights& outlierWeights,
const Matches&
matches)
const;
92 template<
typename T,
typename MatrixA,
typename Vector>
Matrix OutlierWeights
Weights of the associations between the points in Matches and the points in the reference.
PointMatcher< T >::DataPoints DataPoints
PointMatcher< T >::Matrix Matrix
A structure holding data ready for minimization. The data are "normalized", for instance there are no...
PointMatcher< T >::Matches Matches
Parametrizable::ParametersDoc ParametersDoc
static const std::string description()
PointMatcher< T >::OutlierWeights OutlierWeights
PointToPlaneErrorMinimizer(const Parameters ¶ms=Parameters())
TransformationParameters compute_in_place(ErrorElements &mPts)
An error minimizer will compute a transformation matrix such as to minimize the error between the rea...
virtual T getOverlap() const
If not redefined by child class, return the ratio of how many points were used (with weight) for erro...
PointMatcher< T >::Vector Vector
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
virtual TransformationParameters compute(const ErrorElements &mPts)
Find the transformation that minimizes the error given matched pair of points. This function most be ...
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
Functions and classes that are dependant on scalar type are defined in this templatized class...
PointMatcher< T >::ErrorMinimizer::ErrorElements ErrorElements
Result of the data-association step (Matcher::findClosests), before outlier rejection.
PointMatcherSupport::Parametrizable Parametrizable
The documentation of a parameter.
Parametrizable::ParameterDoc ParameterDoc
The superclass of classes that are constructed using generic parameters. This class provides the para...
std::vector< ParameterDoc > ParametersDoc
The documentation of all parameters.
PointMatcher< T >::ErrorMinimizer ErrorMinimizer
PointMatcherSupport::Parametrizable P
void solvePossiblyUnderdeterminedLinearSystem(const MatrixA &A, const Vector &b, Vector &x)
virtual const std::string name()
virtual T getResidualError(const DataPoints &filteredReading, const DataPoints &filteredReference, const OutlierWeights &outlierWeights, const Matches &matches) const
If not redefined by child class, return max value for T.
PointMatcher< T >::TransformationParameters TransformationParameters
Eigen::Matrix< T, Eigen::Dynamic, 1 > Vector
A vector over ScalarType.
Parametrizable::Parameters Parameters
static const ParametersDoc availableParameters()
Matrix TransformationParameters
A matrix holding the parameters a transformation.
static T computeResidualError(ErrorElements mPts, const bool &force2D)