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 "ndt_map/pointcloud_utils.h"
00040 #include "pcl/point_cloud.h"
00041 #include "Eigen/Core"
00042
00043 namespace lslgeneric
00044 {
00045
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& other)
00061 {
00062 this->init(false,other.resolutions);
00063 }
00064
00082 bool match( pcl::PointCloud<pcl::PointXYZ>& target,
00083 pcl::PointCloud<pcl::PointXYZ>& source,
00084 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T );
00085
00086
00098 void check( pcl::PointCloud<pcl::PointXYZ>& fixed,
00099 pcl::PointCloud<pcl::PointXYZ>& moving,
00100 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T
00101
00102 );
00103
00104
00120 bool match( NDTMap& target,
00121 pcl::PointCloud<pcl::PointXYZ>& source,
00122 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T );
00123
00124
00125
00126
00132 bool covariance( pcl::PointCloud<pcl::PointXYZ>& target,
00133 pcl::PointCloud<pcl::PointXYZ>& source,
00134 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T,
00135 Eigen::Matrix<double,6,6> &cov
00136 );
00137
00138
00139 double scorePointCloud(pcl::PointCloud<pcl::PointXYZ> &source,
00140 NDTMap &target);
00141
00142
00143
00144
00145 void derivativesPointCloud(pcl::PointCloud<pcl::PointXYZ> &source,
00146 NDTMap &target,
00147 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> &transform,
00148 Eigen::Matrix<double,6,1> &score_gradient,
00149 Eigen::Matrix<double,6,6> &Hessian,
00150 bool computeHessian);
00151
00152 void generateScoreDebug(const char* out, pcl::PointCloud<pcl::PointXYZ>& target,
00153 pcl::PointCloud<pcl::PointXYZ>& source);
00154
00155 double finalscore;
00156 private:
00157
00158 Eigen::Matrix<double,3,6> Jest;
00159 Eigen::Matrix<double,18,6> Hest;
00160
00161 double lfd1,lfd2;
00162 bool useSimpleDerivatives;
00163 double current_resolution;
00164 bool isIrregularGrid;
00165
00166
00167 void precomputeAngleDerivatives(Eigen::Vector3d &eulerAngles);
00168
00169
00170 bool update_score_gradient(Eigen::Matrix<double,6,1> &score_gradient,
00171 Eigen::Vector3d &transformed,
00172 Eigen::Matrix3d &Cinv);
00173
00174 void update_hessian(Eigen::Matrix<double,6,6> &Hessian,
00175 Eigen::Vector3d &transformed,
00176 Eigen::Matrix3d &Cinv);
00177
00178
00179 void computeDerivatives(pcl::PointXYZ &pt);
00180
00181
00182 double lineSearch(double score_here,
00183 Eigen::Matrix<double,6,1> &score_gradient,
00184 Eigen::Matrix<double,6,1> &increment,
00185 pcl::PointCloud<pcl::PointXYZ> &source,
00186 NDTMap &target) ;
00187
00188
00189
00190 double lineSearchMT( Eigen::Matrix<double,6,1> &score_gradient_init,
00191 Eigen::Matrix<double,6,1> &increment,
00192 pcl::PointCloud<pcl::PointXYZ> &source,
00193 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> &globalT,
00194 NDTMap &target) ;
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204 struct MoreThuente
00205 {
00206 static double min(double a, double b);
00207 static double max(double a, double b);
00208 static double absmax(double a, double b, double c);
00209 static int cstep(double& stx, double& fx, double& dx,
00210 double& sty, double& fy, double& dy,
00211 double& stp, double& fp, double& dp,
00212 bool& brackt, double stmin, double stmax);
00213 };
00214
00215
00216 pcl::PointCloud<pcl::PointXYZ> subsample(pcl::PointCloud<pcl::PointXYZ>& original);
00217 int NUMBER_OF_POINTS;
00218 int NUMBER_OF_ACTIVE_CELLS;
00219
00220 private:
00221
00222 Eigen::Vector3d jest13, jest23, jest04, jest14, jest24, jest05, jest15, jest25;
00223 Eigen::Vector3d a2,a3, b2,b3, c2,c3, d1,d2,d3, e1,e2,e3, f1,f2,f3;
00224
00225 std::vector<double> resolutions;
00226
00227 void init(bool useDefaultGridResolutions, std::vector<double> _resolutions);
00228 double normalizeAngle(double a);
00229 public:
00230 int ITR_MAX;
00231 double subsample_size;
00232 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00233 };
00234
00235 }
00236
00237 #endif