58 return OutlierWeights::Constant(input.
ids.rows(), input.
ids.cols(), 1);
123 const T limit = factor * median;
172 const T tunedRatio = optimizeInlierRatio(input);
183 typedef typename Eigen::Array<T, Eigen::Dynamic, 1> LineArray;
185 const int points_nbr = matches.
dists.rows() * matches.
dists.cols();
188 std::vector<T> tmpSortedDist;
189 tmpSortedDist.reserve(points_nbr);
190 for (
int x = 0;
x < matches.
dists.cols(); ++
x)
191 for (
int y = 0; y < matches.
dists.rows(); ++y)
192 if ((matches.
dists(y,
x) != numeric_limits<T>::infinity()) && (matches.
dists(y,
x) > 0))
193 tmpSortedDist.push_back(matches.
dists(y,
x));
194 if (tmpSortedDist.size() == 0)
195 throw ConvergenceError(
"no outlier to filter");
197 std::sort(tmpSortedDist.begin(), tmpSortedDist.end());
198 std::vector<T> tmpCumSumSortedDist;
199 tmpCumSumSortedDist.reserve(points_nbr);
200 std::partial_sum(tmpSortedDist.begin(), tmpSortedDist.end(), tmpCumSumSortedDist.begin());
202 const int minEl = floor(this->minRatio*points_nbr);
203 const int maxEl = floor(this->maxRatio*points_nbr);
206 Eigen::Map<LineArray> sortedDist(&tmpCumSumSortedDist[0], points_nbr);
208 const LineArray trunkSortedDist = sortedDist.segment(minEl, maxEl-minEl);
210 const LineArray ids = LineArray::LinSpaced(trunkSortedDist.rows(), minEl+1, maxEl);
211 const LineArray ratio = ids / points_nbr;
212 const LineArray deno = ratio.pow(this->lambda);
214 const LineArray FRMS = trunkSortedDist * ids.inverse() * deno.inverse().square() ;
216 FRMS.minCoeff(&minIndex);
217 const T optRatio = (float)(minIndex + minEl)/ (float)points_nbr;
230 warningPrinted(false)
247 if(normalsReading.cols() != 0 && normalsReference.cols() != 0)
249 for (
int x = 0;
x < w.cols(); ++
x)
251 const Vector normalRead = normalsReading.col(
x).normalized();
253 for (
int y = 0; y < w.rows(); ++y)
255 const int idRef = input.
ids(y,
x);
262 const Vector normalRef = normalsReference.col(idRef).normalized();
264 const T value =
anyabs(normalRead.dot(normalRef));
275 if(warningPrinted ==
false)
277 LOG_INFO_STREAM(
"SurfaceNormalOutlierFilter: surface normals not available. Skipping filtering");
278 warningPrinted =
true;
281 w = Matrix::Ones(input.
dists.rows(), input.
dists.cols());
303 (boost::format(
"GenericDescriptorOutlierFilter: Error, the parameter named 'source' can only be set to 'reference' or 'reading' but was set to %1%") %
source).str());
315 const int knn = input.
dists.rows();
316 const int readPtsCount = input.
dists.cols();
322 if(source ==
"reference")
323 cloud = &filteredReference;
325 cloud = &filteredReference;
332 (boost::format(
"GenericDescriptorOutlierFilter: Error, the parameter named 'descName' must be a 1D descriptor but the field %1% is %2%D") % descName % desc.rows()).str());
335 for(
int k=0; k < knn; k++)
337 for(
int i=0; i < readPtsCount; i++)
339 const int idRead = input.
ids(k, i);
344 if(useSoftThreshold ==
false)
346 if(useLargerThan ==
true)
348 if (desc(0, idRead) > threshold)
355 if (desc(0, idRead) < threshold)
364 w(k,i) = desc(0, idRead);
383 {
"cauchy", RobustFctId::Cauchy},
384 {
"welsch", RobustFctId::Welsch},
385 {
"sc", RobustFctId::SwitchableConstraint},
386 {
"gm", RobustFctId::GM},
387 {
"tukey", RobustFctId::Tukey},
388 {
"huber", RobustFctId::Huber},
389 {
"L1", RobustFctId::L1},
390 {
"student", RobustFctId::Student}
409 const set<string> validScaleEstimator = {
"none",
"mad",
"berg",
"std"};
410 if (validScaleEstimator.find(
scaleEstimator) == validScaleEstimator.end()) {
413 const set<string> validDistanceType = {
"point2point",
"point2plane"};
414 if (validDistanceType.find(
distanceType) == validDistanceType.end()) {
446 if (robustFcts.find(robustFctName) == robustFcts.end())
450 robustFctId = robustFcts[robustFctName];
459 return this->robustFiltering(filteredReading, filteredReference, input);
471 int nbr_read_point = input.
dists.cols();
472 int nbr_match = input.
dists.rows();
476 Vector reading_point(Vector::Zero(3));
477 Vector reference_point(Vector::Zero(3));
480 Matrix dists(Matrix::Zero(nbr_match, nbr_read_point));
482 for(
int i = 0; i < nbr_read_point; ++i)
484 reading_point = reading.
features.block(0, i, 3, 1);
485 for(
int j = 0; j < nbr_match; ++j)
487 const int reference_idx = input.
ids(j, i);
489 reference_point = reference.
features.block(0, reference_idx, 3, 1);
491 normal = normals.col(reference_idx).normalized();
493 dists(j, i) =
pow(normal.dot(reading_point-reference_point), 2);
507 if (scaleEstimator ==
"mad")
509 if (iteration <= nbIterationForScale or nbIterationForScale == 0)
513 }
else if (scaleEstimator ==
"std")
515 if (iteration <= nbIterationForScale or nbIterationForScale == 0)
519 }
else if (scaleEstimator ==
"berg")
521 if (iteration <= nbIterationForScale or nbIterationForScale == 0)
531 const T CONVERGENCE_RATE = 0.85;
532 scale = CONVERGENCE_RATE * (scale - berg_target_scale) + berg_target_scale;
542 Matrix dists = distanceType ==
"point2point" ? input.
dists : computePointToPlaneDistance(filteredReading, filteredReference, input);
545 Array e2 = dists.array() / (scale * scale);
549 Array w, aboveThres, belowThres;
550 switch (robustFctId) {
551 case RobustFctId::Cauchy:
554 case RobustFctId::Welsch:
555 w = (-e2 / k2).exp();
557 case RobustFctId::SwitchableConstraint:
558 aboveThres = 4.0 * k2 * ((k + e2).square()).
inverse();
559 w = (e2 >= k).select(aboveThres, 1.0);
561 case RobustFctId::GM:
562 w = k2*((k + e2).square()).
inverse();
564 case RobustFctId::Tukey:
565 belowThres = (1 - e2 / k2).square();
566 w = (e2 >= k2).select(0.0, belowThres);
568 case RobustFctId::Huber:
569 aboveThres = k * (e2.sqrt().inverse());
570 w = (e2 >= k2).select(aboveThres, 1.0);
572 case RobustFctId::L1:
573 w = e2.sqrt().inverse();
575 case RobustFctId::Student: {
577 auto p = (1 + e2 / k).
pow(-(k +
d) / 2);
578 w = p * (k +
d) * (k + e2).inverse();
587 const double ARBITRARY_SMALL_VALUE = 1e-50;
588 w = (w.array() <= ARBITRARY_SMALL_VALUE).select(ARBITRARY_SMALL_VALUE, w);
591 if(squaredApproximation != std::numeric_limits<T>::infinity())
594 w = (e2 >= squaredApproximation).select(0.0, w);