Go to the documentation of this file.
50 nbRejectedMatches(-1),
53 weightedPointUsedRatio(-1.0)
67 assert(outlierWeights.rows() ==
matches.
ids.rows());
69 const int knn = outlierWeights.rows();
70 const int dimFeat = requestedPts.
features.rows();
71 const int dimReqDesc = requestedPts.
descriptors.rows();
72 const int dimReqTime = requestedPts.
times.rows();
75 const int pointsCount = (outlierWeights.array() != 0.0).count();
79 Matrix keptFeat(dimFeat, pointsCount);
83 keptDesc =
Matrix(dimReqDesc, pointsCount);
89 Matches keptMatches (Dists(1,pointsCount), Ids(1, pointsCount));
93 int rejectedMatchCount = 0;
94 int rejectedPointCount = 0;
95 bool matchExist =
false;
98 for (
int i = 0; i < requestedPts.
features.cols(); ++i)
101 for(
int k = 0; k <
knn; k++)
108 if (outlierWeights(k,i) != 0.0)
114 keptTime.col(j) = requestedPts.
times.col(i);
117 keptFeat.col(j) = requestedPts.
features.col(i);
119 keptMatches.
dists(0, j) = matchDist;
120 keptWeights(0,j) = outlierWeights(k,i);
127 rejectedMatchCount++;
131 if(matchExist ==
false)
133 rejectedPointCount++;
137 assert(j == pointsCount);
142 assert(dimFeat == sourcePts.
features.rows());
143 const int dimSourDesc = sourcePts.
descriptors.rows();
144 const int dimSourTime = sourcePts.
times.rows();
146 Matrix associatedFeat(dimFeat, pointsCount);
150 associatedDesc =
Matrix(dimSourDesc, pointsCount);
154 associatedTime =
Int64Matrix(dimSourTime, pointsCount);
157 for (
int i = 0; i < pointsCount; ++i)
159 const int refIndex(keptMatches.
ids(i));
160 associatedFeat.col(i) = sourcePts.
features.block(0, refIndex, dimFeat, 1);
163 associatedDesc.col(i) = sourcePts.
descriptors.block(0, refIndex, dimSourDesc, 1);
166 associatedTime.col(i) = sourcePts.
times.block(0, refIndex, dimSourTime, 1);
190 this->matches = keptMatches;
228 this->lastErrorElements = matchedPoints;
238 return lastErrorElements.pointUsedRatio;
246 return lastErrorElements;
253 return lastErrorElements.weightedPointUsedRatio;
260 LOG_WARNING_STREAM(
"ErrorMinimizer - warning, no specific method to compute overlap was provided for the ErrorMinimizer used.");
261 return lastErrorElements.weightedPointUsedRatio;
268 LOG_WARNING_STREAM(
"ErrorMinimizer - warning, no specific method to compute covariance was provided for the ErrorMinimizer used.");
269 return Matrix::Zero(6,6);
276 LOG_WARNING_STREAM(
"ErrorMinimizer - warning, no specific method to compute residual was provided for the ErrorMinimizer used.");
277 return std::numeric_limits<T>::max();
287 assert(A.cols() == B.cols());
290 assert(A.rows() -1 == B.rows());
293 assert(A.rows() == 4 || A.rows() == 3);
295 const unsigned int x = 0;
296 const unsigned int y = 1;
297 const unsigned int z = 2;
302 cross =
Matrix(B.rows(), B.cols());
304 cross.row(
x) = A.row(y).array() * B.row(z).array() - A.row(z).array() * B.row(y).array();
305 cross.row(y) = A.row(z).array() * B.row(
x).array() - A.row(
x).array() * B.row(z).array();
306 cross.row(z) = A.row(
x).array() * B.row(y).array() - A.row(y).array() * B.row(
x).array();
312 cross = A.row(
x).array() * B.row(y).array() - A.row(y).array() * B.row(
x).array();
int nbRejectedPoints
number of points with all matches set to zero weights
Matrix Dists
Squared distances to closest points, dense matrix of ScalarType.
Dists dists
squared distances to closest points
Labels descriptorLabels
labels of descriptors
virtual Matrix getCovariance() const
If not redefined by child class, return zero matrix.
Ids ids
identifiers of closest points
Matrix OutlierWeights
Weights of the associations between the points in Matches and the points in the reference.
ErrorElements getErrorElements() const
Return the last the ErrorElements structure that was used for error minimization.
PM::DataPoints DataPoints
T pointUsedRatio
the ratio of how many points were used for error minimization
static Matrix crossProduct(const Matrix &A, const Matrix &B)
Helper funtion doing the cross product in 3D and a pseudo cross product in 2D.
Functions and classes that are dependant on scalar type are defined in this templatized class.
Point matcher did not converge.
ErrorElements()
Constructor without data.
T getPointUsedRatio() const
Return the ratio of how many points were used for error minimization.
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.
virtual T getOverlap() const
If not redefined by child class, return the ratio of how many points were used (with weight) for erro...
Labels timeLabels
labels of times.
T getWeightedPointUsedRatio() const
Return the ratio of how many points were used (with weight) for error minimization.
Eigen::Matrix< std::int64_t, Eigen::Dynamic, Eigen::Dynamic > Int64Matrix
A dense signed 64-bits matrix.
ErrorMinimizer()
Construct without parameter.
A structure holding data ready for minimization. The data are "normalized", for instance there are no...
std::vector< ParameterDoc > ParametersDoc
The documentation of all parameters.
Labels featureLabels
labels of features
Matches matches
associations
T weightedPointUsedRatio
the ratio of how many points were used (with weight) for error minimization
Matrix descriptors
descriptors of points in the cloud, might be empty
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
DataPoints reading
reading point cloud
IntMatrix Ids
Identifiers of closest points, dense matrix of integers.
#define LOG_WARNING_STREAM(args)
Matrix features
features of points in the cloud
DataPoints reference
reference point cloud
Eigen::Matrix< T, Eigen::Dynamic, 1 > Vector
A vector over ScalarType.
Result of the data-association step (Matcher::findClosests), before outlier rejection.
Int64Matrix times
time associated to each points, might be empty
The superclass of classes that are constructed using generic parameters. This class provides the para...
OutlierWeights weights
weights for every association
int nbRejectedMatches
number of matches with zero weights
virtual ~ErrorMinimizer()
virtual destructor
An error minimizer will compute a transformation matrix such as to minimize the error between the rea...
const std::string className
name of the class
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
virtual TransformationParameters compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const OutlierWeights &outlierWeights, const Matches &matches)
Find the transformation that minimizes the error.
Matrix TransformationParameters
A matrix holding the parameters a transformation.
static constexpr T InvalidDist
In case of too few matches the ids are filled with InvalidId.