00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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>::Vector Vector;
00057
00058 struct NullOutlierFilter: public OutlierFilter
00059 {
00060 inline static const std::string description()
00061 {
00062 return "Does nothing.";
00063 }
00064
00065 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00066 };
00067
00068 struct MaxDistOutlierFilter: public OutlierFilter
00069 {
00070 inline static const std::string description()
00071 {
00072 return "This filter considers as outlier links whose norms are above a fix threshold.";
00073 }
00074 inline static const ParametersDoc availableParameters()
00075 {
00076 return boost::assign::list_of<ParameterDoc>
00077 ( "maxDist", "threshold distance (Euclidean norm)", "1", "0.0000001", "inf", &P::Comp<T>)
00078 ;
00079 }
00080
00081 const T maxDist;
00082
00083 MaxDistOutlierFilter(const Parameters& params = Parameters());
00084 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00085 };
00086
00087
00088 struct MinDistOutlierFilter: public OutlierFilter
00089 {
00090 inline static const std::string description()
00091 {
00092 return "This filter considers as outlier links whose norms are below a threshold.";
00093 }
00094 inline static const ParametersDoc availableParameters()
00095 {
00096 return boost::assign::list_of<ParameterDoc>
00097 ( "minDist", "threshold distance (Euclidean norm)", "1", "0.0000001", "inf", &P::Comp<T>)
00098 ;
00099 }
00100
00101 const T minDist;
00102
00103 MinDistOutlierFilter(const Parameters& params = Parameters());
00104 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00105 };
00106
00107 struct MedianDistOutlierFilter: public OutlierFilter
00108 {
00109 inline static const std::string description()
00110 {
00111 return "This filter considers as outlier links whose norms are above the median link norms times a factor. Based on \\cite{Diebel2004Median}.";
00112 }
00113 inline static const ParametersDoc availableParameters()
00114 {
00115 return boost::assign::list_of<ParameterDoc>
00116 ( "factor", "points farther away factor * median will be considered outliers.", "3", "0.0000001", "inf", &P::Comp<T>)
00117 ;
00118 }
00119
00120 const T factor;
00121
00122 MedianDistOutlierFilter(const Parameters& params = Parameters());
00123 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00124 };
00125
00126 struct TrimmedDistOutlierFilter: public OutlierFilter
00127 {
00128 inline static const std::string description()
00129 {
00130 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}.";
00131 }
00132 inline static const ParametersDoc availableParameters()
00133 {
00134 return boost::assign::list_of<ParameterDoc>
00135 ( "ratio", "percentage to keep", "0.85", "0.0000001", "0.9999999", &P::Comp<T>)
00136 ;
00137 }
00138
00139 const T ratio;
00140
00141 TrimmedDistOutlierFilter(const Parameters& params = Parameters());
00142 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00143 };
00144
00145 struct VarTrimmedDistOutlierFilter: public OutlierFilter
00146 {
00147 inline static const std::string description()
00148 {
00149 return "Hard rejection threshold using quantile and variable ratio. Based on \\cite{Phillips2007VarTrimmed}.";
00150 }
00151 inline static const ParametersDoc availableParameters()
00152 {
00153 return boost::assign::list_of<ParameterDoc>
00154 ( "minRatio", "min ratio", "0.05", "0.0000001", "1", &P::Comp<T>)
00155 ( "maxRatio", "max ratio", "0.99", "0.0000001", "1", &P::Comp<T>)
00156 ( "lambda", "lambda (part of the term that balance the rmsd: 1/ratio^lambda", "0.95" )
00157 ;
00158 }
00159
00160 const T minRatio;
00161 const T maxRatio;
00162 const T lambda;
00163
00164 VarTrimmedDistOutlierFilter(const Parameters& params = Parameters());
00165 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00166
00167 private:
00168
00169 T optimizeInlierRatio(const Matches& matches);
00170 };
00171
00172
00173
00174 struct SurfaceNormalOutlierFilter: public OutlierFilter
00175 {
00176 inline static const std::string description()
00177 {
00178 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.";
00179 }
00180 inline static const ParametersDoc availableParameters()
00181 {
00182 return boost::assign::list_of<ParameterDoc>
00183 ( "maxAngle", "Maximum authorised angle between the 2 surface normals (in radian)", "1.57", "0.0", "3.1416", &P::Comp<T>)
00184 ;
00185 }
00186
00187 const T eps;
00188 bool warningPrinted;
00189
00190 SurfaceNormalOutlierFilter(const Parameters& params = Parameters());
00191 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00192 };
00193
00194 struct GenericDescriptorOutlierFilter: public OutlierFilter
00195 {
00196 inline static const std::string description()
00197 {
00198 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.";
00199 }
00200 inline static const ParametersDoc availableParameters()
00201 {
00202 return boost::assign::list_of<ParameterDoc>
00203 ( "source", "Point cloud from which the descriptor will be used: reference or reading", "reference")
00204 ( "descName", "Descriptor name used to weight paired points", "none")
00205 ( "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>)
00206 ( "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>)
00207 ( "threshold", "Value used to determine the binary weights", "0.1", "0.0000001", "inf", &P::Comp<T>)
00208 ;
00209 }
00210
00211 const std::string source;
00212 const std::string descName;
00213 const bool useSoftThreshold;
00214 const bool useLargerThan;
00215 const T threshold;
00216
00217 GenericDescriptorOutlierFilter(const Parameters& params = Parameters());
00218 virtual OutlierWeights compute(const DataPoints& filteredReading, const DataPoints& filteredReference, const Matches& input);
00219 };
00220
00221 };
00222
00223 #endif // __POINTMATCHER_OUTLIERFILTERS_H