OutlierFiltersImpl.h
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 #ifndef __POINTMATCHER_OUTLIERFILTERS_H
37 #define __POINTMATCHER_OUTLIERFILTERS_H
38 
39 #include "PointMatcher.h"
40 
41 template<typename T>
43 {
50 
55  typedef typename PointMatcher<T>::Matrix Matrix;
56  typedef typename PointMatcher<T>::Array Array;
57  typedef typename PointMatcher<T>::Vector Vector;
58 
59  struct NullOutlierFilter: public OutlierFilter
60  {
61  inline static const std::string description()
62  {
63  return "Does nothing.";
64  }
65 
66  NullOutlierFilter() : OutlierFilter("NullOutlierFilter", ParametersDoc(), Parameters()) {}
67  virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
68  };
69 
70  struct MaxDistOutlierFilter: public OutlierFilter
71  {
72  inline static const std::string description()
73  {
74  return "This filter considers as outlier links whose norms are above a fix threshold.";
75  }
76  inline static const ParametersDoc availableParameters()
77  {
78  return {
79  {"maxDist", "threshold distance (Euclidean norm)", "1", "0.0000001", "inf", &P::Comp<T>}
80  };
81  }
82 
83  const T maxDist;
84 
85  MaxDistOutlierFilter(const Parameters& params = Parameters());
86  virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
87  };
88 
89  //FIXME: is that useful in any case?
90  struct MinDistOutlierFilter: public OutlierFilter
91  {
92  inline static const std::string description()
93  {
94  return "This filter considers as outlier links whose norms are below a threshold.";
95  }
96  inline static const ParametersDoc availableParameters()
97  {
98  return {
99  {"minDist","threshold distance (Euclidean norm)", "1", "0.0000001", "inf", &P::Comp<T> }
100  };
101  }
102 
103  const T minDist;
104 
105  MinDistOutlierFilter(const Parameters& params = Parameters());
106  virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
107  };
108 
109  struct MedianDistOutlierFilter: public OutlierFilter
110  {
111  inline static const std::string description()
112  {
113  return "This filter considers as outlier links whose norms are above the median link norms times a factor. Based on \\cite{Diebel2004Median}.";
114  }
115  inline static const ParametersDoc availableParameters()
116  {
117  return {
118  {"factor","points farther away factor * median will be considered outliers.", "3", "0.0000001", "inf", &P::Comp <T>}
119  };
120  }
121 
122  const T factor;
123 
124  MedianDistOutlierFilter(const Parameters& params = Parameters());
125  virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
126  };
127 
128  struct TrimmedDistOutlierFilter: public OutlierFilter
129  {
130  inline static const std::string description()
131  {
132  return "Hard rejection threshold using quantile. This filter considers as inlier a certain percentage of the links with the smallest norms. Based on \\cite{Chetverikov2002Trimmed}.";
133  }
134  inline static const ParametersDoc availableParameters()
135  {
136  return {
137  {"ratio", "percentage to keep", "0.85", "0.0000001", "1.0", &P::Comp<T>}
138  };
139  }
140 
141  const T ratio;
142 
143  TrimmedDistOutlierFilter(const Parameters& params = Parameters());
144  virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
145  };
146 
147  struct VarTrimmedDistOutlierFilter: public OutlierFilter
148  {
149  inline static const std::string description()
150  {
151  return "Hard rejection threshold using quantile and variable ratio. Based on \\cite{Phillips2007VarTrimmed}.";
152  }
153  inline static const ParametersDoc availableParameters()
154  {
155  return {
156  {"minRatio", "min ratio", "0.05","0.0000001", "1", &P::Comp<T>},
157  {"maxRatio", "max ratio", "0.99", "0.0000001", "1", &P::Comp<T>},
158  {"lambda", "lambda (part of the term that balance the rmsd: 1/ratio^lambda", "2.35"}
159  };
160  }
161 
162  const T minRatio;
163  const T maxRatio;
164  const T lambda;
165 
166  VarTrimmedDistOutlierFilter(const Parameters& params = Parameters());
167  virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
168 
169  private:
170  // return the optimized ratio
171  T optimizeInlierRatio(const Matches& matches);
172  };
173 
174 
175  // ---------------------------------
176  struct SurfaceNormalOutlierFilter: public OutlierFilter
177  {
178  inline static const std::string description()
179  {
180  return "Hard rejection threshold using the angle between the surface normal vector of the reading and the reference. Usually used in combination with `OrientNormalDataPointsFilter`. If normal vectors are not in the descriptor for both of the point clouds, does nothing.";
181  }
182  inline static const ParametersDoc availableParameters()
183  {
184  return {
185  {"maxAngle", "Maximum authorised angle between the 2 surface normals (in radian)", "1.57", "0.0", "3.1416", &P::Comp<T>}
186  };
187  }
188 
189  const T eps;
191 
192  SurfaceNormalOutlierFilter(const Parameters& params = Parameters());
193  virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
194  };
195 
196  struct GenericDescriptorOutlierFilter: public OutlierFilter
197  {
198  inline static const std::string description()
199  {
200  return "This filter weights matched points based on a 1D descriptor of either a single point cloud (either the reference or the reading). The descriptor values must be larger than zero.";
201  }
202  inline static const ParametersDoc availableParameters()
203  {
204  return {
205  { "source", "Point cloud from which the descriptor will be used: reference or reading", "reference"},
206  { "descName", "Descriptor name used to weight paired points", "none"},
207  { "useSoftThreshold", "If set to 1 (true), uses the value of the descriptor as a weight. If set to 0 (false), uses the parameter 'threshold' to set binary weights.", "0", "0", "1", P::Comp<bool>},
208  { "useLargerThan", "If set to 1 (true), values over the 'threshold' will have a weight of one. If set to 0 (false), values under the 'threshold' will have a weight of one. All other values will have a weight of zero.", "1", "0", "1", P::Comp<bool>},
209  { "threshold", "Value used to determine the binary weights", "0.1", "0.0000001", "inf", &P::Comp<T>}
210  };
211  }
212 
215  const bool useSoftThreshold;
216  const bool useLargerThan;
217  const T threshold;
218 
219  GenericDescriptorOutlierFilter(const Parameters& params = Parameters());
220  virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
221  };
222 
223  struct RobustOutlierFilter: public OutlierFilter
224  {
225 
226  inline static const std::string description()
227  {
228  return "Robust weight function. 8 robust functions to choose from (Cauchy, Welsch, Switchable Constraint, Geman-McClure, Tukey, Huber, L1 and Student). All the functions are M-Estimator (\\cite{RobustWeightFunctions}) except L1 and Student.";
229  }
230  inline static const ParametersDoc availableParameters()
231  {
232  return {
233  {"robustFct", "Type of robust function used. Available fct: 'cauchy', 'welsch', 'sc'(aka Switchable-Constraint), 'gm' (aka Geman-McClure), 'tukey', 'huber' and 'L1'. (Default: cauchy)", "cauchy"},
234  {"tuning", "Tuning parameter used to limit the influence of outliers."
235  "If the 'scaleEstimator' is 'mad' or 'none', this parameter acts as the tuning parameter."
236  "If the 'scaleEstimator' is 'berg' this parameter acts as the target scale (σ*).", "1.0", "0.0000001", "inf", &P::Comp<T>},
237  {"scaleEstimator", "The scale estimator is used to convert the error distance into a Mahalanobis distance. 3 estimators are available: "
238  "'none': no estimator (scale = 1), "
239  "'mad': use the median of absolute deviation (a kind of robust standard deviation), "
240  "'berg': an iterative exponentially decreasing estimator", "mad"},
241  {"nbIterationForScale", "For how many iteration the 'scaleEstimator' is recalculated. After 'nbIterationForScale' iteration the previous scale is kept. A nbIterationForScale==0 means that the estiamtor is recalculated at each iteration.", "0", "0", "100", &P::Comp<int>},
242  {"distanceType", "Type of error distance used, either point to point ('point2point') or point to plane('point2plane'). Point to point gives better result normally.", "point2point"},
243  {"approximation", "If the matched distance is larger than this threshold, its weight will be forced to zero. This can save computation as zero values are not minimized. If set to inf (default value), no approximation is done. The unit of this parameter is the same as the distance used, typically meters.", "inf", "0.0", "inf", &P::Comp<T>}
244  };
245  }
246 
247  Matrix computePointToPlaneDistance(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
248  virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
249  RobustOutlierFilter(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
250  RobustOutlierFilter(const Parameters& params = Parameters());
251  protected:
252  enum RobustFctId {
253  Cauchy=0,
254  Welsch=1,
255  SwitchableConstraint=2,
256  GM=3,
257  Tukey=4,
258  Huber=5,
259  L1=6,
260  Student=7
261  };
262  typedef std::map<std::string, RobustFctId> RobustFctMap;
263  static RobustFctMap robustFcts;
274 
275 
276  virtual void resolveEstimatorName();
277  virtual OutlierWeights robustFiltering(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
278  };
279 
280 }; // OutlierFiltersImpl
281 
282 #endif // __POINTMATCHER_OUTLIERFILTERS_H
Matrix OutlierWeights
Weights of the associations between the points in Matches and the points in the reference.
Definition: PointMatcher.h:397
public interface
PointMatcher< T >::Vector Vector
Parametrizable::InvalidParameter InvalidParameter
Parametrizable::Parameters Parameters
PointMatcherSupport::Parametrizable P
::std::string string
Definition: gtest.h:1979
PointMatcher< T >::DataPoints DataPoints
std::map< std::string, RobustFctId > RobustFctMap
PointMatcher< T >::OutlierFilter OutlierFilter
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
Definition: PointMatcher.h:169
PointMatcher< T >::Matches Matches
PointMatcher< T >::Matrix Matrix
PointMatcher< T >::OutlierWeights OutlierWeights
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
Result of the data-association step (Matcher::findClosests), before outlier rejection.
Definition: PointMatcher.h:371
PointMatcherSupport::Parametrizable Parametrizable
An outlier filter removes or weights links between points in reading and their matched points in refe...
Definition: PointMatcher.h:499
The documentation of a parameter.
PointMatcher< T >::Array Array
The superclass of classes that are constructed using generic parameters. This class provides the para...
An exception thrown when one tries to fetch the value of an unexisting parameter. ...
std::vector< ParameterDoc > ParametersDoc
The documentation of all parameters.
static const ParametersDoc availableParameters()
static const std::string description()
const std::string className
name of the class
static const ParametersDoc availableParameters()
static const ParametersDoc availableParameters()
static const ParametersDoc availableParameters()
Eigen::Array< T, Eigen::Dynamic, Eigen::Dynamic > Array
A dense array over ScalarType.
Definition: PointMatcher.h:175
Eigen::Matrix< T, Eigen::Dynamic, 1 > Vector
A vector over ScalarType.
Definition: PointMatcher.h:161
Parametrizable::ParametersDoc ParametersDoc
static const ParametersDoc availableParameters()
Parametrizable::ParameterDoc ParameterDoc
virtual OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Detect outliers using features.


libpointmatcher
Author(s):
autogenerated on Sat May 27 2023 02:38:02