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 #ifndef NDT_MATCHER_HH
00036 #define NDT_MATCHER_HH
00037
00038 #include "ndt_map/ndt_map.h"
00039 #include "pcl/point_cloud.h"
00040 #include "Eigen/Core"
00041
00042 namespace lslgeneric
00043 {
00044
00048 template <typename PointSource, typename PointTarget>
00049 class NDTMatcherP2D
00050 {
00051 public:
00052 NDTMatcherP2D(std::vector<double> _resolutions)
00053 {
00054 this->init(false,_resolutions);
00055 }
00056 NDTMatcherP2D()
00057 {
00058 this->init(true,std::vector<double>());
00059 }
00060 NDTMatcherP2D(const NDTMatcherP2D<PointSource,PointTarget>& other)
00061 {
00062 this->init(false,other.resolutions);
00063 }
00077 bool match( pcl::PointCloud<PointTarget>& target,
00078 pcl::PointCloud<PointSource>& source,
00079 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T );
00080
00092 bool match( NDTMap<PointTarget>& target,
00093 pcl::PointCloud<PointSource>& source,
00094 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T );
00095
00101 bool covariance( pcl::PointCloud<PointTarget>& target,
00102 pcl::PointCloud<PointSource>& source,
00103 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T,
00104 Eigen::Matrix<double,6,6> &cov
00105 );
00106
00107
00108 double scorePointCloud(pcl::PointCloud<PointSource> &source,
00109 NDTMap<PointTarget> &target);
00110
00111
00112
00113
00114 void derivativesPointCloud(pcl::PointCloud<PointSource> &source,
00115 NDTMap<PointTarget> &target,
00116 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> &transform,
00117 Eigen::Matrix<double,6,1> &score_gradient,
00118 Eigen::Matrix<double,6,6> &Hessian,
00119 bool computeHessian);
00120
00121 void generateScoreDebug(const char* out, pcl::PointCloud<PointTarget>& target,
00122 pcl::PointCloud<PointSource>& source);
00123
00124 double finalscore;
00125 private:
00126
00127 Eigen::Matrix<double,3,6> Jest;
00128 Eigen::Matrix<double,18,6> Hest;
00129
00130 double lfd1,lfd2;
00131 bool useSimpleDerivatives;
00132 double current_resolution;
00133 bool isIrregularGrid;
00134
00135
00136 void precomputeAngleDerivatives(Eigen::Vector3d &eulerAngles);
00137
00138
00139 bool update_score_gradient(Eigen::Matrix<double,6,1> &score_gradient,
00140 Eigen::Vector3d &transformed,
00141 Eigen::Matrix3d &Cinv);
00142
00143 void update_hessian(Eigen::Matrix<double,6,6> &Hessian,
00144 Eigen::Vector3d &transformed,
00145 Eigen::Matrix3d &Cinv);
00146
00147
00148 void computeDerivatives(PointSource &pt);
00149
00150
00151 double lineSearch(double score_here,
00152 Eigen::Matrix<double,6,1> &score_gradient,
00153 Eigen::Matrix<double,6,1> &increment,
00154 pcl::PointCloud<PointSource> &source,
00155 NDTMap<PointTarget> &target) ;
00156
00157
00158
00159 double lineSearchMT( Eigen::Matrix<double,6,1> &score_gradient_init,
00160 Eigen::Matrix<double,6,1> &increment,
00161 pcl::PointCloud<PointSource> &source,
00162 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> &globalT,
00163 NDTMap<PointTarget> &target) ;
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173 struct MoreThuente
00174 {
00175 static double min(double a, double b);
00176 static double max(double a, double b);
00177 static double absmax(double a, double b, double c);
00178 static int cstep(double& stx, double& fx, double& dx,
00179 double& sty, double& fy, double& dy,
00180 double& stp, double& fp, double& dp,
00181 bool& brackt, double stmin, double stmax);
00182 };
00183
00184
00185 pcl::PointCloud<PointSource> subsample(pcl::PointCloud<PointSource>& original);
00186 int NUMBER_OF_POINTS;
00187 int NUMBER_OF_ACTIVE_CELLS;
00188
00189 private:
00190
00191 Eigen::Vector3d jest13, jest23, jest04, jest14, jest24, jest05, jest15, jest25;
00192 Eigen::Vector3d a2,a3, b2,b3, c2,c3, d1,d2,d3, e1,e2,e3, f1,f2,f3;
00193
00194 std::vector<double> resolutions;
00195
00196 void init(bool useDefaultGridResolutions, std::vector<double> _resolutions);
00197 double normalizeAngle(double a);
00198 public:
00199 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00200 };
00201
00202 }
00203
00204 #include <ndt_registration/impl/ndt_matcher_p2d.hpp>
00205
00206 #endif