Go to the documentation of this file.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_TRANSFORMATIONCHECKERS_H
00037 #define __POINTMATCHER_TRANSFORMATIONCHECKERS_H
00038
00039 #include "PointMatcher.h"
00040
00041 template<typename T>
00042 struct TransformationCheckersImpl
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
00050 typedef typename PointMatcher<T>::TransformationChecker TransformationChecker;
00051 typedef typename PointMatcher<T>::TransformationParameters TransformationParameters;
00052 typedef typename PointMatcher<T>::Vector Vector;
00053 typedef typename PointMatcher<T>::VectorVector VectorVector;
00054 typedef typename PointMatcher<T>::Quaternion Quaternion;
00055 typedef typename PointMatcher<T>::QuaternionVector QuaternionVector;
00056 typedef typename PointMatcher<T>::Matrix Matrix;
00057
00058 struct CounterTransformationChecker: public TransformationChecker
00059 {
00060 inline static const std::string description()
00061 {
00062 return "This checker stops the ICP loop after a certain number of iterations.";
00063 }
00064 inline static const ParametersDoc availableParameters()
00065 {
00066 return boost::assign::list_of<ParameterDoc>
00067 ( "maxIterationCount", "maximum number of iterations ", "40", "0", "2147483647", &P::Comp<unsigned> )
00068 ;
00069 }
00070
00071 const unsigned maxIterationCount;
00072
00073 CounterTransformationChecker(const Parameters& params = Parameters());
00074 virtual void init(const TransformationParameters& parameters, bool& iterate);
00075 virtual void check(const TransformationParameters& parameters, bool& iterate);
00076 };
00077
00078 struct DifferentialTransformationChecker: public TransformationChecker
00079 {
00080 inline static const std::string description()
00081 {
00082 return "This checker stops the ICP loop when the relative motions (i.e. abs(currentIter - lastIter)) of rotation and translation components are below a fix thresholds. This allows to stop the iteration when the point cloud is stabilized. Smoothing can be applied to avoid oscillations. Inspired by \\cite{Chetverikov2002Trimmed}.";
00083 }
00084 inline static const ParametersDoc availableParameters()
00085 {
00086 return boost::assign::list_of<ParameterDoc>
00087 ( "minDiffRotErr", "threshold for rotation error (radian)", "0.001", "0.", "6.2831854", &P::Comp<T> )
00088 ( "minDiffTransErr", "threshold for translation error", "0.001", "0.", "inf", &P::Comp<T> )
00089 ( "smoothLength", "number of iterations over which to average the differencial error", "3", "0", "2147483647", &P::Comp<unsigned> )
00090 ;
00091 }
00092
00093 const T minDiffRotErr;
00094 const T minDiffTransErr;
00095 const unsigned int smoothLength;
00096
00097 protected:
00098 QuaternionVector rotations;
00099 VectorVector translations;
00100
00101 public:
00102 DifferentialTransformationChecker(const Parameters& params = Parameters());
00103
00104 virtual void init(const TransformationParameters& parameters, bool& iterate);
00105 virtual void check(const TransformationParameters& parameters, bool& iterate);
00106 };
00107
00108 struct BoundTransformationChecker: public TransformationChecker
00109 {
00110 inline static const std::string description()
00111 {
00112 return "This checker stops the ICP loop with an exception when the transformation values exceed bounds.";
00113 }
00114 inline static const ParametersDoc availableParameters()
00115 {
00116 return boost::assign::list_of<ParameterDoc>
00117 ( "maxRotationNorm", "rotation bound", "1", "0", "inf", &P::Comp<T> )
00118 ( "maxTranslationNorm", "translation bound", "1", "0", "inf", &P::Comp<T> )
00119 ;
00120 }
00121
00122 const T maxRotationNorm;
00123 const T maxTranslationNorm;
00124
00125 protected:
00126 Quaternion initialRotation3D;
00127 T initialRotation2D;
00128 Vector initialTranslation;
00129
00130 public:
00131 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00132 BoundTransformationChecker(const Parameters& params = Parameters());
00133 virtual void init(const TransformationParameters& parameters, bool& iterate);
00134 virtual void check(const TransformationParameters& parameters, bool& iterate);
00135 };
00136 };
00137
00138 #endif // __POINTMATCHER_TRANSFORMATIONCHECKERS_H