40 using namespace Eigen;
68 const T w_sum_inv =
T(1.)/w.sum();
70 (mPts.
reading.
features.topRows(dimCount-1).array().rowwise() * w.array().transpose()).rowwise().sum() * w_sum_inv;
71 const Vector meanReference =
72 (mPts.
reference.
features.topRows(dimCount-1).array().rowwise() * w.array().transpose()).rowwise().sum() * w_sum_inv;
82 const JacobiSVD<Matrix> svd(m, ComputeThinU | ComputeThinV);
83 Matrix rotMatrix(svd.matrixU() * svd.matrixV().transpose());
88 if (rotMatrix.determinant() < 0.)
90 Matrix tmpV = svd.matrixV().transpose();
91 tmpV.row(dimCount-2) *= -1.;
92 rotMatrix = svd.matrixU() * tmpV;
94 const Vector trVector(meanReference - rotMatrix * meanReading);
96 Matrix result(Matrix::Identity(dimCount, dimCount));
97 result.topLeftCorner(dimCount-1, dimCount-1) = rotMatrix;
98 result.topRightCorner(dimCount-1, 1) = trVector;
110 assert(matches.
ids.rows() > 0);
128 throw std::runtime_error(
"Error, last error element empty. Error minimizer needs to be called at least once before using this method.");
133 LOG_INFO_STREAM(
"PointToPointErrorMinimizer - warning, no sensor noise found. Using best estimate given outlier rejection instead.");
140 const T mean = dists.sum()/nbPoints;
143 for(
int i=0; i < nbPoints; i++)
145 if(dists(i) < (mean + noises(0,i)))
151 return (
T)count/(
T)nbPoints;
162 Matrix deltaNorms = deltas.colwise().norm();
163 return deltaNorms.sum();
#define LOG_INFO_STREAM(args)
A structure holding data ready for minimization. The data are "normalized", for instance there are no...
PointMatcher< T >::OutlierWeights OutlierWeights
TransformationParameters compute_in_place(ErrorElements &mPts)
ConstView getDescriptorViewByName(const std::string &name) const
Get a const view on a descriptor by name, throw an exception if it does not exist.
PointToPointErrorMinimizer()
DataPoints reference
reference point cloud
An error minimizer will compute a transformation matrix such as to minimize the error between the rea...
PointMatcher< T >::Matrix Matrix
T getWeightedPointUsedRatio() const
Return the ratio of how many points were used (with weight) for error minimization.
OutlierWeights weights
weights for every association
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.
Functions and classes that are dependant on scalar type are defined in this templatized class...
Parametrizable::ParametersDoc ParametersDoc
virtual TransformationParameters compute(const ErrorElements &mPts)
Find the transformation that minimizes the error given matched pair of points. This function most be ...
Result of the data-association step (Matcher::findClosests), before outlier rejection.
bool descriptorExists(const std::string &name) const
Look if a descriptor with a given name exist.
static T computeResidualError(const ErrorElements &mPts)
ErrorElements lastErrorElements
memory of the last computed error
const std::string className
name of the class
PointMatcher< T >::Vector Vector
Ids ids
identifiers of closest points
Matrix features
features of points in the cloud
DataPoints reading
reading point cloud
Parametrizable::Parameters Parameters
Matrix TransformationParameters
A matrix holding the parameters a transformation.
virtual T getOverlap() const
If not redefined by child class, return the ratio of how many points were used (with weight) for erro...