36 #ifndef __POINTMATCHER_OUTLIERFILTERS_H 37 #define __POINTMATCHER_OUTLIERFILTERS_H 63 return "Does nothing.";
67 virtual OutlierWeights
compute(
const DataPoints& filteredReading,
const DataPoints& filteredReference,
const Matches& input);
74 return "This filter considers as outlier links whose norms are above a fix threshold.";
79 {
"maxDist",
"threshold distance (Euclidean norm)",
"1",
"0.0000001",
"inf", &P::Comp<T>}
86 virtual OutlierWeights
compute(
const DataPoints& filteredReading,
const DataPoints& filteredReference,
const Matches& input);
94 return "This filter considers as outlier links whose norms are below a threshold.";
99 {
"minDist",
"threshold distance (Euclidean norm)",
"1",
"0.0000001",
"inf", &P::Comp<T> }
106 virtual OutlierWeights
compute(
const DataPoints& filteredReading,
const DataPoints& filteredReference,
const Matches& input);
113 return "This filter considers as outlier links whose norms are above the median link norms times a factor. Based on \\cite{Diebel2004Median}.";
118 {
"factor",
"points farther away factor * median will be considered outliers.",
"3",
"0.0000001",
"inf", &P::Comp <T>}
125 virtual OutlierWeights
compute(
const DataPoints& filteredReading,
const DataPoints& filteredReference,
const Matches& input);
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}.";
137 {
"ratio",
"percentage to keep",
"0.85",
"0.0000001",
"1.0", &P::Comp<T>}
144 virtual OutlierWeights
compute(
const DataPoints& filteredReading,
const DataPoints& filteredReference,
const Matches& input);
151 return "Hard rejection threshold using quantile and variable ratio. Based on \\cite{Phillips2007VarTrimmed}.";
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"}
167 virtual OutlierWeights
compute(
const DataPoints& filteredReading,
const DataPoints& filteredReference,
const Matches& input);
171 T optimizeInlierRatio(
const Matches&
matches);
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.";
185 {
"maxAngle",
"Maximum authorised angle between the 2 surface normals (in radian)",
"1.57",
"0.0",
"3.1416", &P::Comp<T>}
193 virtual OutlierWeights
compute(
const DataPoints& filteredReading,
const DataPoints& filteredReference,
const Matches& input);
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.";
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>}
220 virtual OutlierWeights
compute(
const DataPoints& filteredReading,
const DataPoints& filteredReference,
const Matches& input);
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.";
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>}
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);
255 SwitchableConstraint=2,
276 virtual void resolveEstimatorName();
277 virtual OutlierWeights robustFiltering(
const DataPoints& filteredReading,
const DataPoints& filteredReference,
const Matches& input);
282 #endif // __POINTMATCHER_OUTLIERFILTERS_H Matrix OutlierWeights
Weights of the associations between the points in Matches and the points in the reference.
const std::string distanceType
static const std::string description()
const std::string robustFctName
PointMatcher< T >::Vector Vector
static const std::string description()
Parametrizable::InvalidParameter InvalidParameter
Parametrizable::Parameters Parameters
PointMatcherSupport::Parametrizable P
static const ParametersDoc availableParameters()
const std::string scaleEstimator
static const std::string description()
static const std::string description()
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.
PointMatcher< T >::Matches Matches
PointMatcher< T >::Matrix Matrix
PointMatcher< T >::OutlierWeights OutlierWeights
const std::string descName
static const ParametersDoc availableParameters()
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
static RobustFctMap robustFcts
Result of the data-association step (Matcher::findClosests), before outlier rejection.
static const ParametersDoc availableParameters()
PointMatcherSupport::Parametrizable Parametrizable
An outlier filter removes or weights links between points in reading and their matched points in refe...
The documentation of a parameter.
PointMatcher< T >::Array Array
const T squaredApproximation
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
const int nbIterationForScale
const bool useSoftThreshold
static const ParametersDoc availableParameters()
static const ParametersDoc availableParameters()
static const std::string description()
static const ParametersDoc availableParameters()
Eigen::Array< T, Eigen::Dynamic, Eigen::Dynamic > Array
A dense array over ScalarType.
Eigen::Matrix< T, Eigen::Dynamic, 1 > Vector
A vector over ScalarType.
Parametrizable::ParametersDoc ParametersDoc
static const std::string description()
static const std::string description()
Parametrizable::ParameterDoc ParameterDoc
virtual OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Detect outliers using features.