OutlierFiltersImpl.cpp
Go to the documentation of this file.
1 // kate: replace-tabs off; indent-width 4; indent-mode normal
2 // vim: ts=4:sw=4:noexpandtab
3 /*
4 
5 Copyright (c) 2010--2012,
6 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
7 You can contact the authors at <f dot pomerleau at gmail dot com> and
8 <stephane at magnenat dot net>
9 
10 All rights reserved.
11 
12 Redistribution and use in source and binary forms, with or without
13 modification, are permitted provided that the following conditions are met:
14  * Redistributions of source code must retain the above copyright
15  notice, this list of conditions and the following disclaimer.
16  * Redistributions in binary form must reproduce the above copyright
17  notice, this list of conditions and the following disclaimer in the
18  documentation and/or other materials provided with the distribution.
19  * Neither the name of the <organization> nor the
20  names of its contributors may be used to endorse or promote products
21  derived from this software without specific prior written permission.
22 
23 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
24 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
25 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
26 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
27 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
28 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
30 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
31 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
32 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
33 
34 */
35 
36 #include "OutlierFiltersImpl.h"
37 #include "PointMatcherPrivate.h"
38 #include "Functions.h"
39 #include "MatchersImpl.h"
40 
41 #include <algorithm>
42 #include <vector>
43 #include <iostream>
44 #include <limits>
45 #include <numeric>
46 #include <ciso646>
47 
48 using namespace std;
49 using namespace PointMatcherSupport;
50 
51 // NullOutlierFilter
52 template<typename T>
54  const DataPoints& filteredReading,
55  const DataPoints& filteredReference,
56  const Matches& input)
57 {
58  return OutlierWeights::Constant(input.ids.rows(), input.ids.cols(), 1);
59 }
60 
63 
64 
65 // MaxDistOutlierFilter
66 template<typename T>
68  OutlierFilter("MaxDistOutlierFilter", MaxDistOutlierFilter::availableParameters(), params),
69  maxDist(pow(Parametrizable::get<T>("maxDist"),2)) // we use the square distance later
70 {
71 }
72 
73 
74 template<typename T>
76  const DataPoints& filteredReading,
77  const DataPoints& filteredReference,
78  const Matches& input)
79 {
80  return OutlierWeights((input.dists.array() <= maxDist).template cast<T>());
81 }
82 
85 
86 // MinDistOutlierFilter
87 template<typename T>
89  OutlierFilter("MinDistOutlierFilter", MinDistOutlierFilter::availableParameters(), params),
90  minDist(pow(Parametrizable::get<T>("minDist"),2))// Note: we use the square distance later
91 {
92 }
93 
94 template<typename T>
96  const DataPoints& filteredReading,
97  const DataPoints& filteredReference,
98  const Matches& input)
99 {
100  return OutlierWeights((input.dists.array() >= minDist).template cast<T>());
101 }
102 
105 
106 
107 
108 // MedianDistOutlierFilter
109 template<typename T>
111  OutlierFilter("MedianDistOutlierFilter", MedianDistOutlierFilter::availableParameters(), params),
112  factor(Parametrizable::get<T>("factor"))
113 {
114 }
115 
116 template<typename T>
118  const DataPoints& filteredReading,
119  const DataPoints& filteredReference,
120  const Matches& input)
121 {
122  const T median = input.getDistsQuantile(0.5);
123  const T limit = factor * median;
124  return OutlierWeights((input.dists.array() <= limit).template cast<T>());
125 }
126 
129 
130 
131 // TrimmedDistOutlierFilter
132 template<typename T>
134  OutlierFilter("TrimmedDistOutlierFilter", TrimmedDistOutlierFilter::availableParameters(), params),
135  ratio(Parametrizable::get<T>("ratio"))
136 {
137 }
138 
139 template<typename T>
141  const DataPoints& filteredReading,
142  const DataPoints& filteredReference,
143  const Matches& input)
144 {
145  const T limit = input.getDistsQuantile(ratio);
146  return OutlierWeights((input.dists.array() <= limit).template cast<T>());
147 }
148 
151 
152 // VarTrimmedDistOutlierFilter
153 template<typename T>
155  OutlierFilter("VarTrimmedDistOutlierFilter", VarTrimmedDistOutlierFilter::availableParameters(), params),
156  minRatio(Parametrizable::get<T>("minRatio")),
157  maxRatio(Parametrizable::get<T>("maxRatio")),
158  lambda(Parametrizable::get<T>("lambda"))
159 {
160  if (this->minRatio >= this->maxRatio)
161  {
162  throw InvalidParameter((boost::format("VarTrimmedDistOutlierFilter: minRatio (%1%) should be smaller than maxRatio (%2%)") % minRatio % maxRatio).str());
163  }
164 }
165 
166 template<typename T>
168  const DataPoints& filteredReading,
169  const DataPoints& filteredReference,
170  const Matches& input)
171 {
172  const T tunedRatio = optimizeInlierRatio(input);
173  LOG_INFO_STREAM("Optimized ratio: " << tunedRatio);
174 
175  const T limit = input.getDistsQuantile(tunedRatio);
176  return OutlierWeights((input.dists.array() <= limit).template cast<T>());
177 }
178 
179 template<typename T>
181 {
182  typedef typename PointMatcher<T>::ConvergenceError ConvergenceError;
183  typedef typename Eigen::Array<T, Eigen::Dynamic, 1> LineArray;
184 
185  const int points_nbr = matches.dists.rows() * matches.dists.cols();
186 
187  // vector containing the squared distances of the matches
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");
196 
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());
201 
202  const int minEl = floor(this->minRatio*points_nbr);
203  const int maxEl = floor(this->maxRatio*points_nbr);
204 
205  // Return std::vector to an eigen::vector
206  Eigen::Map<LineArray> sortedDist(&tmpCumSumSortedDist[0], points_nbr);
207 
208  const LineArray trunkSortedDist = sortedDist.segment(minEl, maxEl-minEl);
209 
210  const LineArray ids = LineArray::LinSpaced(trunkSortedDist.rows(), minEl+1, maxEl);
211  const LineArray ratio = ids / points_nbr; // ratio for each of element between minEl and maxEl
212  const LineArray deno = ratio.pow(this->lambda); // f^λ
213  // frms = cumSumDists[minEl:maxEl] / id / (f^λ)²
214  const LineArray FRMS = trunkSortedDist * ids.inverse() * deno.inverse().square() ;
215  int minIndex(0);// = FRMS.minCoeff();
216  FRMS.minCoeff(&minIndex);
217  const T optRatio = (float)(minIndex + minEl)/ (float)points_nbr;
218 
219  return optRatio;
220 }
221 
224 
225 // SurfaceNormalOutlierFilter
226 template<typename T>
228  OutlierFilter("SurfaceNormalOutlierFilter", SurfaceNormalOutlierFilter::availableParameters(), params),
229  eps(cos(Parametrizable::get<T>("maxAngle"))),
230  warningPrinted(false)
231 {
232  //warning: eps is change to cos(maxAngle)!
233 }
234 
235 template<typename T>
237  const DataPoints& filteredReading,
238  const DataPoints& filteredReference,
239  const Matches& input)
240 {
241  const BOOST_AUTO(normalsReading, filteredReading.getDescriptorViewByName("normals"));
242  const BOOST_AUTO(normalsReference, filteredReference.getDescriptorViewByName("normals"));
243 
244  // select weight from median
245  OutlierWeights w(input.dists.rows(), input.dists.cols());
246 
247  if(normalsReading.cols() != 0 && normalsReference.cols() != 0)
248  {
249  for (int x = 0; x < w.cols(); ++x) // pts in reading
250  {
251  const Vector normalRead = normalsReading.col(x).normalized();
252 
253  for (int y = 0; y < w.rows(); ++y) // knn
254  {
255  const int idRef = input.ids(y, x);
256 
257  if (idRef == MatchersImpl<T>::NNS::InvalidIndex) {
258  w(y, x) = 0;
259  continue;
260  }
261 
262  const Vector normalRef = normalsReference.col(idRef).normalized();
263 
264  const T value = anyabs(normalRead.dot(normalRef));
265 
266  if(value < eps) // test to keep the points
267  w(y, x) = 0;
268  else
269  w(y, x) = 1;
270  }
271  }
272  }
273  else
274  {
275  if(warningPrinted == false)
276  {
277  LOG_INFO_STREAM("SurfaceNormalOutlierFilter: surface normals not available. Skipping filtering");
278  warningPrinted = true;
279  }
280 
281  w = Matrix::Ones(input.dists.rows(), input.dists.cols());
282  }
283  //abort();
284  return w;
285 }
286 
289 
290 // GenericDescriptorOutlierFilter
291 template<typename T>
293  OutlierFilter("GenericDescriptorOutlierFilter", GenericDescriptorOutlierFilter::availableParameters(), params),
294  source(Parametrizable::getParamValueString("source")),
295  descName(Parametrizable::getParamValueString("descName")),
296  useSoftThreshold(Parametrizable::get<bool>("useSoftThreshold")),
297  useLargerThan(Parametrizable::get<bool>("useLargerThan")),
298  threshold(Parametrizable::get<T>("threshold"))
299 {
300  if(source != "reference" && source != "reading")
301  {
302  throw InvalidParameter(
303  (boost::format("GenericDescriptorOutlierFilter: Error, the parameter named 'source' can only be set to 'reference' or 'reading' but was set to %1%") % source).str());
304  }
305 }
306 
307 template<typename T>
309  const DataPoints& filteredReading,
310  const DataPoints& filteredReference,
311  const Matches& input)
312 {
313  typedef typename DataPoints::ConstView ConstView;
314 
315  const int knn = input.dists.rows();
316  const int readPtsCount = input.dists.cols();
317 
318  OutlierWeights w(knn, readPtsCount);
319 
320  const DataPoints *cloud;
321 
322  if(source == "reference")
323  cloud = &filteredReference;
324  else
325  cloud = &filteredReference;
326 
327  ConstView desc(cloud->getDescriptorViewByName(descName));
328 
329  if(desc.rows() != 1)
330  {
331  throw InvalidParameter(
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());
333  }
334 
335  for(int k=0; k < knn; k++)
336  {
337  for(int i=0; i < readPtsCount; i++)
338  {
339  const int idRead = input.ids(k, i);
340  if (idRead == MatchersImpl<T>::NNS::InvalidIndex){
341  w(k,i) = 0;
342  continue;
343  }
344  if(useSoftThreshold == false)
345  {
346  if(useLargerThan == true)
347  {
348  if (desc(0, idRead) > threshold)
349  w(k,i) = 1;
350  else
351  w(k,i) = 0;
352  }
353  else
354  {
355  if (desc(0, idRead) < threshold)
356  w(k,i) = 1;
357  else
358  w(k,i) = 0;
359  }
360  }
361  else
362  {
363  // use soft threshold by assigning the weight using the descriptor
364  w(k,i) = desc(0, idRead);
365  }
366  }
367  }
368 
369  //Normalize
370  if(useSoftThreshold)
371  w = w/w.maxCoeff();
372 
373  return w;
374 }
375 
378 
379 // RobustOutlierFilter
380 template<typename T>
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}
391 };
392 
393 template<typename T>
395  const ParametersDoc paramsDoc,
396  const Parameters& params):
397  OutlierFilter(className, paramsDoc, params),
398  robustFctName(Parametrizable::get<string>("robustFct")),
399  tuning(Parametrizable::get<T>("tuning")),
400  squaredApproximation(pow(Parametrizable::get<T>("approximation"), 2)),
401  scaleEstimator(Parametrizable::get<string>("scaleEstimator")),
402  nbIterationForScale(Parametrizable::get<int>("nbIterationForScale")),
403  distanceType(Parametrizable::get<string>("distanceType")),
404  robustFctId(-1),
405  iteration(1),
406  scale(0.0),
407  berg_target_scale(0)
408 {
409  const set<string> validScaleEstimator = {"none", "mad", "berg", "std"};
410  if (validScaleEstimator.find(scaleEstimator) == validScaleEstimator.end()) {
411  throw InvalidParameter("Invalid scale estimator name.");
412  }
413  const set<string> validDistanceType = {"point2point", "point2plane"};
414  if (validDistanceType.find(distanceType) == validDistanceType.end()) {
415  throw InvalidParameter("Invalid distance type name.");
416  }
417 
419 
420  if (scaleEstimator == "berg") {
422 
423  // See \cite{Bergstrom2014}
424  if (robustFctId == RobustFctId::Cauchy)
425  {
426  tuning = 4.3040;
427  } else if (robustFctId == RobustFctId::Tukey)
428  {
429  tuning = 7.0589;
430  } else if (robustFctId == RobustFctId::Huber)
431  {
432  tuning = 2.0138;
433  }
434  }
435 }
436 
437 template<typename T>
439  RobustOutlierFilter("RobustOutlierFilter", RobustOutlierFilter::availableParameters(), params)
440 {
441 }
442 
443 
444 template<typename T>
446  if (robustFcts.find(robustFctName) == robustFcts.end())
447  {
448  throw InvalidParameter("Invalid robust function name.");
449  }
451 }
452 
453  template<typename T>
455  const DataPoints& filteredReading,
456  const DataPoints& filteredReference,
457  const Matches& input)
458 {
459  return this->robustFiltering(filteredReading, filteredReference, input);
460 }
461 
462 
463 
464 template<typename T>
467  const DataPoints& reading,
468  const DataPoints& reference,
469  const Matches& input) {
470 
471  int nbr_read_point = input.dists.cols();
472  int nbr_match = input.dists.rows();
473 
474  Matrix normals = reference.getDescriptorViewByName("normals");
475 
476  Vector reading_point(Vector::Zero(3));
477  Vector reference_point(Vector::Zero(3));
478  Vector normal(3);
479 
480  Matrix dists(Matrix::Zero(nbr_match, nbr_read_point));
481 
482  for(int i = 0; i < nbr_read_point; ++i)
483  {
484  reading_point = reading.features.block(0, i, 3, 1);
485  for(int j = 0; j < nbr_match; ++j)
486  {
487  const int reference_idx = input.ids(j, i);
488  if (reference_idx != Matches::InvalidId) {
489  reference_point = reference.features.block(0, reference_idx, 3, 1);
490 
491  normal = normals.col(reference_idx).normalized();
492  // distance_point_to_plan = dot(n, p-q)²
493  dists(j, i) = pow(normal.dot(reading_point-reference_point), 2);
494  }
495  }
496  }
497 
498  return dists;
499 }
500 
501 template<typename T>
503  const DataPoints& filteredReading,
504  const DataPoints& filteredReference,
505  const Matches& input) {
506 
507  if (scaleEstimator == "mad")
508  {
510  {
511  scale = sqrt(input.getMedianAbsDeviation());
512  }
513  } else if (scaleEstimator == "std")
514  {
516  {
517  scale = sqrt(input.getStandardDeviation());
518  }
519  } else if (scaleEstimator == "berg")
520  {
522  {
523  // The tuning constant is the target scale that we want to reach
524  // It's a bit confusing to use the tuning constant for scaling...
525  if (iteration == 1)
526  {
527  scale = 1.9 * sqrt(input.getDistsQuantile(0.5));
528  }
529  else
530  { // TODO: maybe add it has another parameter or make him a function of the max iteration
531  const T CONVERGENCE_RATE = 0.85;
532  scale = CONVERGENCE_RATE * (scale - berg_target_scale) + berg_target_scale;
533  }
534  }
535  }
536  else
537  {
538  scale = 1.0; // We don't rescale
539  }
540  iteration++;
541 
542  Matrix dists = distanceType == "point2point" ? input.dists : computePointToPlaneDistance(filteredReading, filteredReference, input);
543 
544  // e² = scaled squared distance
545  Array e2 = dists.array() / (scale * scale);
546 
547  T k = tuning;
548  const T k2 = k * k;
549  Array w, aboveThres, belowThres;
550  switch (robustFctId) {
551  case RobustFctId::Cauchy: // 1/(1 + e²/k²)
552  w = (1 + e2 / k2).inverse();
553  break;
554  case RobustFctId::Welsch: // exp(-e²/k²)
555  w = (-e2 / k2).exp();
556  break;
557  case RobustFctId::SwitchableConstraint: // if e² > k then 4 * k²/(k + e²)²
558  aboveThres = 4.0 * k2 * ((k + e2).square()).inverse();
559  w = (e2 >= k).select(aboveThres, 1.0);
560  break;
561  case RobustFctId::GM: // k²/(k + e²)²
562  w = k2*((k + e2).square()).inverse();
563  break;
564  case RobustFctId::Tukey: // if e² < k² then (1-e²/k²)²
565  belowThres = (1 - e2 / k2).square();
566  w = (e2 >= k2).select(0.0, belowThres);
567  break;
568  case RobustFctId::Huber: // if |e| >= k then k/|e| = k/sqrt(e²)
569  aboveThres = k * (e2.sqrt().inverse());
570  w = (e2 >= k2).select(aboveThres, 1.0);
571  break;
572  case RobustFctId::L1: // 1/|e| = 1/sqrt(e²)
573  w = e2.sqrt().inverse();
574  break;
575  case RobustFctId::Student: { // ....
576  const T d = 3;
577  auto p = (1 + e2 / k).pow(-(k + d) / 2);
578  w = p * (k + d) * (k + e2).inverse();
579  break;
580  }
581  default:
582  break;
583  }
584 
585  // In the minimizer, zero weight are ignored, we want them to be notice by having the smallest value
586  // The value can not be a numeric limit, since they might cause a nan/inf.
587  const double ARBITRARY_SMALL_VALUE = 1e-50;
588  w = (w.array() <= ARBITRARY_SMALL_VALUE).select(ARBITRARY_SMALL_VALUE, w);
589 
590 
591  if(squaredApproximation != std::numeric_limits<T>::infinity())
592  {
593  //Note from Eigen documentation: (if statement).select(then matrix, else matrix)
594  w = (e2 >= squaredApproximation).select(0.0, w);
595  }
596 
597  return w;
598 }
599 
600 
Matrix OutlierWeights
Weights of the associations between the points in Matches and the points in the reference.
Definition: PointMatcher.h:397
d
virtual OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Detect outliers using features.
#define LOG_INFO_STREAM(args)
MaxDistOutlierFilter(const Parameters &params=Parameters())
PointMatcher< T >::Vector Vector
constexpr T pow(const T base, const std::size_t exponent)
Definition: utils.h:47
virtual OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Detect outliers using features.
Parametrizable::InvalidParameter InvalidParameter
Matrix computePointToPlaneDistance(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
x
Definition: test.py:4
GenericDescriptorOutlierFilter(const Parameters &params=Parameters())
Point matcher did not converge.
Definition: PointMatcher.h:148
ConstView getDescriptorViewByName(const std::string &name) const
Get a const view on a descriptor by name, throw an exception if it does not exist.
virtual OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Detect outliers using features.
::std::string string
Definition: gtest.h:1979
VarTrimmedDistOutlierFilter(const Parameters &params=Parameters())
virtual OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Detect outliers using features.
virtual OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Detect outliers using features.
std::map< std::string, RobustFctId > RobustFctMap
RobustOutlierFilter(const std::string &className, const ParametersDoc paramsDoc, const Parameters &params)
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
Definition: PointMatcher.h:169
PointMatcher< T >::Matrix Matrix
PointMatcher< T >::OutlierWeights OutlierWeights
virtual OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Detect outliers using features.
T getDistsQuantile(const T quantile) const
Get the distance at the T-ratio closest point.
Definition: Matches.cpp:61
SurfaceNormalOutlierFilter(const Parameters &params=Parameters())
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
Functions and classes that are not dependant on scalar type are defined in this namespace.
const Eigen::Block< const Matrix > ConstView
A view on a const feature or const descriptor.
Definition: PointMatcher.h:214
TF2SIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
Result of the data-association step (Matcher::findClosests), before outlier rejection.
Definition: PointMatcher.h:371
An outlier filter removes or weights links between points in reading and their matched points in refe...
Definition: PointMatcher.h:496
const M::mapped_type & get(const M &m, const typename M::key_type &k)
PointMatcher< T >::Array Array
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
MinDistOutlierFilter(const Parameters &params=Parameters())
INLINE Rall1d< T, V, S > exp(const Rall1d< T, V, S > &arg)
The superclass of classes that are constructed using generic parameters. This class provides the para...
std::string getParamValueString(const std::string &paramName)
Get the value of a parameter, as a string.
std::vector< ParameterDoc > ParametersDoc
The documentation of all parameters.
static const ParametersDoc availableParameters()
S get(const std::string &paramName)
Return the value of paramName, lexically-casted to S.
const std::string className
name of the class
TrimmedDistOutlierFilter(const Parameters &params=Parameters())
static const ParametersDoc availableParameters()
virtual OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Detect outliers using features.
Dists dists
squared distances to closest points
Definition: PointMatcher.h:384
static const ParametersDoc availableParameters()
static const ParametersDoc availableParameters()
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
virtual OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Detect outliers using features.
T getStandardDeviation() const
Definition: Matches.cpp:125
Matrix features
features of points in the cloud
Definition: PointMatcher.h:331
Ids ids
identifiers of closest points
Definition: PointMatcher.h:385
static constexpr int InvalidId
Definition: PointMatcher.h:377
static const ParametersDoc availableParameters()
MedianDistOutlierFilter(const Parameters &params=Parameters())
static T anyabs(const T &v)
Definition: Functions.h:44
virtual OutlierWeights robustFiltering(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
T getMedianAbsDeviation() const
Calculate the Median of Absolute Deviation(MAD), which is median(|x-median(x)|), a kind of robust sta...
Definition: Matches.cpp:91
virtual OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Detect outliers using features.


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Thu Jun 1 2023 03:06:43