OutlierFiltersImpl.h
Go to the documentation of this file.
00001 // kate: replace-tabs off; indent-width 4; indent-mode normal
00002 // vim: ts=4:sw=4:noexpandtab
00003 /*
00004 
00005 Copyright (c) 2010--2012,
00006 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
00007 You can contact the authors at <f dot pomerleau at gmail dot com> and
00008 <stephane at magnenat dot net>
00009 
00010 All rights reserved.
00011 
00012 Redistribution and use in source and binary forms, with or without
00013 modification, are permitted provided that the following conditions are met:
00014     * Redistributions of source code must retain the above copyright
00015       notice, this list of conditions and the following disclaimer.
00016     * Redistributions in binary form must reproduce the above copyright
00017       notice, this list of conditions and the following disclaimer in the
00018       documentation and/or other materials provided with the distribution.
00019     * Neither the name of the <organization> nor the
00020       names of its contributors may be used to endorse or promote products
00021       derived from this software without specific prior written permission.
00022 
00023 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00024 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00025 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00026 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
00027 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00028 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00030 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00031 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00032 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00033 
00034 */
00035 
00036 #ifndef __POINTMATCHER_OUTLIERFILTERS_H
00037 #define __POINTMATCHER_OUTLIERFILTERS_H
00038 
00039 #include "PointMatcher.h"
00040 
00041 template<typename T>
00042 struct OutlierFiltersImpl
00043 {
00044         typedef PointMatcherSupport::Parametrizable Parametrizable;
00045         typedef PointMatcherSupport::Parametrizable P;
00046         typedef Parametrizable::Parameters Parameters;
00047         typedef Parametrizable::ParameterDoc ParameterDoc;
00048         typedef Parametrizable::ParametersDoc ParametersDoc;
00049         typedef Parametrizable::InvalidParameter InvalidParameter;
00050         
00051         typedef typename PointMatcher<T>::DataPoints DataPoints;
00052         typedef typename PointMatcher<T>::Matches Matches;
00053         typedef typename PointMatcher<T>::OutlierFilter OutlierFilter;
00054         typedef typename PointMatcher<T>::OutlierWeights OutlierWeights;
00055         typedef typename PointMatcher<T>::Matrix Matrix;
00056         typedef typename PointMatcher<T>::Array Array;
00057         typedef typename PointMatcher<T>::Vector Vector;
00058         
00059         struct NullOutlierFilter: public OutlierFilter
00060         {
00061                 inline static const std::string description()
00062                 {
00063                         return "Does nothing.";
00064                 }
00065 
00066                 NullOutlierFilter() : OutlierFilter("NullOutlierFilter",  ParametersDoc(), Parameters()) {}
00067                 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00068         };
00069 
00070         struct MaxDistOutlierFilter: public OutlierFilter
00071         {
00072                 inline static const std::string description()
00073                 {
00074                         return "This filter considers as outlier links whose norms are above a fix threshold.";
00075                 }
00076                 inline static const ParametersDoc availableParameters()
00077                 {
00078                         return {
00079                                 {"maxDist", "threshold distance (Euclidean norm)", "1", "0.0000001", "inf", &P::Comp<T>}
00080                         };
00081                 }
00082                 
00083                 const T maxDist;
00084                 
00085                 MaxDistOutlierFilter(const Parameters& params = Parameters());
00086                 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00087         };
00088 
00089         //FIXME: is that useful in any case?
00090         struct MinDistOutlierFilter: public OutlierFilter
00091         {
00092                 inline static const std::string description()
00093                 {
00094                         return "This filter considers as outlier links whose norms are below a threshold.";
00095                 }
00096                 inline static const ParametersDoc availableParameters()
00097                 {
00098                         return {
00099                                 {"minDist","threshold distance (Euclidean norm)", "1", "0.0000001", "inf", &P::Comp<T> }
00100                         };
00101                 }
00102                 
00103                 const T minDist;
00104                 
00105                 MinDistOutlierFilter(const Parameters& params = Parameters()); 
00106                 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00107         };
00108 
00109         struct MedianDistOutlierFilter: public OutlierFilter 
00110         {
00111                 inline static const std::string description()
00112                 {
00113                         return "This filter considers as outlier links whose norms are above the median link norms times a factor. Based on \\cite{Diebel2004Median}.";
00114                 }
00115                 inline static const ParametersDoc availableParameters()
00116                 {
00117                         return {
00118                                 {"factor","points farther away factor * median will be considered outliers.", "3", "0.0000001", "inf", &P::Comp <T>}
00119                         };
00120                 }
00121                 
00122                 const T factor;
00123                 
00124                 MedianDistOutlierFilter(const Parameters& params = Parameters());
00125                 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00126         };
00127 
00128         struct TrimmedDistOutlierFilter: public OutlierFilter
00129         {
00130                 inline static const std::string description()
00131                 {
00132                         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}.";
00133                 }
00134                 inline static const ParametersDoc availableParameters()
00135                 {
00136                         return {
00137                                 {"ratio", "percentage to keep", "0.85", "0.0000001", "1.0", &P::Comp<T>}
00138                         };
00139                 }
00140                 
00141                 const T ratio;
00142                 
00143                 TrimmedDistOutlierFilter(const Parameters& params = Parameters());
00144                 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00145         };
00146 
00147         struct VarTrimmedDistOutlierFilter: public OutlierFilter
00148         {
00149                 inline static const std::string description()
00150                 {
00151                         return "Hard rejection threshold using quantile and variable ratio. Based on \\cite{Phillips2007VarTrimmed}.";
00152                 }
00153                 inline static const ParametersDoc availableParameters()
00154                 {
00155                         return {
00156                                 {"minRatio", "min ratio", "0.05","0.0000001", "1", &P::Comp<T>},
00157                                 {"maxRatio", "max ratio", "0.99", "0.0000001", "1", &P::Comp<T>},
00158                                 {"lambda", "lambda (part of the term that balance the rmsd: 1/ratio^lambda", "2.35"}
00159                         };
00160                 }
00161 
00162                 const T minRatio;
00163                 const T maxRatio;
00164                 const T lambda;
00165                 
00166                 VarTrimmedDistOutlierFilter(const Parameters& params = Parameters());
00167                 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00168                 
00169         private:
00170                 // return the optimized ratio
00171                 T optimizeInlierRatio(const Matches& matches);
00172         };
00173         
00174         
00175         // ---------------------------------
00176         struct SurfaceNormalOutlierFilter: public OutlierFilter
00177         {
00178                 inline static const std::string description()
00179                 {
00180                         return "Hard rejection threshold using the angle between the surface normal vector of the reading and the reference. If normal vectors or not in the descriptor for both of the point clouds, does nothing.";
00181                 }
00182                 inline static const ParametersDoc availableParameters()
00183                 {
00184                         return {
00185                                 {"maxAngle", "Maximum authorised angle between the 2 surface normals (in radian)", "1.57", "0.0", "3.1416", &P::Comp<T>}
00186                         };
00187                 }
00188 
00189                 const T eps;
00190                 bool warningPrinted;
00191                 
00192                 SurfaceNormalOutlierFilter(const Parameters& params = Parameters());
00193                 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00194         };
00195 
00196         struct GenericDescriptorOutlierFilter: public OutlierFilter
00197         {
00198                 inline static const std::string description()
00199                 {
00200                         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.";
00201                 }
00202                 inline static const ParametersDoc availableParameters()
00203                 {
00204                         return {
00205                                 { "source", "Point cloud from which the descriptor will be used: reference or reading", "reference"},
00206                                 { "descName", "Descriptor name used to weight paired points", "none"},
00207                                 { "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>},
00208                                 { "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>},
00209                                 { "threshold", "Value used to determine the binary weights", "0.1", "0.0000001", "inf", &P::Comp<T>}
00210                         };
00211                 }
00212                 
00213                 const std::string source;
00214                 const std::string descName;
00215                 const bool useSoftThreshold;
00216                 const bool useLargerThan;
00217                 const T threshold;
00218                 
00219                 GenericDescriptorOutlierFilter(const Parameters& params = Parameters());
00220                 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00221         };
00222 
00223         struct RobustOutlierFilter: public OutlierFilter
00224         {
00225 
00226                 inline static const std::string description()
00227                 {
00228                         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.";
00229                 }
00230                 inline static const ParametersDoc availableParameters()
00231                 {
00232                         return {
00233                                 {"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"},
00234                                 {"tuning", "Tuning parameter used to limit the influence of outliers."
00235                                   "If the 'scaleEstimator' is 'mad' or 'none', this parameter acts as the tuning parameter."
00236                                   "If the 'scaleEstimator' is 'berg' this parameter acts as the target scale (σ*).", "1.0", "0.0000001", "inf", &P::Comp<T>},
00237                                 {"scaleEstimator", "The scale estimator is used to convert the error distance into a Mahalanobis distance. 3 estimators are available: "
00238                                   "'none': no estimator (scale = 1), "
00239                                   "'mad': use the median of absolute deviation (a kind of robust standard deviation), "
00240                                   "'berg': an iterative exponentially decreasing estimator", "mad"},
00241                                 {"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>},
00242                                 {"distanceType", "Type of error distance used, either point to point ('point2point') or point to plane('point2plane'). Point to point gives better result normally.", "point2point"},
00243                                 {"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>}
00244                         };
00245                 }
00246 
00247                 Matrix computePointToPlaneDistance(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00248                 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00249                 RobustOutlierFilter(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params);
00250                 RobustOutlierFilter(const Parameters& params = Parameters());
00251                 protected:
00252                 enum RobustFctId {
00253                         Cauchy=0,
00254                         Welsch=1,
00255                         SwitchableConstraint=2,
00256                         GM=3,
00257                         Tukey=4,
00258                         Huber=5,
00259                         L1=6,
00260                         Student=7
00261                 };
00262                 typedef std::map<std::string, RobustFctId> RobustFctMap;
00263                 static RobustFctMap robustFcts;
00264                 const std::string robustFctName;
00265                 T tuning;
00266                 const T squaredApproximation;
00267                 const std::string scaleEstimator;
00268                 const int nbIterationForScale;
00269                 const std::string distanceType;
00270                 int robustFctId;
00271                 int iteration;
00272                 T scale;
00273                 T berg_target_scale;
00274 
00275 
00276                 virtual void resolveEstimatorName();
00277                 virtual OutlierWeights robustFiltering(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00278         };
00279 
00280 }; // OutlierFiltersImpl
00281 
00282 #endif // __POINTMATCHER_OUTLIERFILTERS_H


libpointmatcher
Author(s):
autogenerated on Thu Jun 20 2019 19:51:32