00001 #ifndef NDT_MCL_HPP_
00002 #define NDT_MCL_HPP_
00003 #include <pcl/ros/conversions.h>
00004 #include <pcl/point_cloud.h>
00005 #include <pcl/io/pcd_io.h>
00006 #include <pcl/point_types.h>
00007 #include <tf_conversions/tf_eigen.h>
00008 #include <cstdio>
00009 #include <Eigen/Eigen>
00010 #include <Eigen/Geometry>
00011 #include <fstream>
00012
00013 #include <ndt_map/ndt_map.h>
00014 #include <ndt_map/ndt_cell.h>
00015 #include <pointcloud_vrml/pointcloud_utils.h>
00016 #include "ndt_mcl/CParticleFilter.h"
00020 template <typename PointT>
00021 class NDTMCL{
00022 public:
00023 lslgeneric::NDTMap<PointT> map;
00024 mcl::CParticleFilter pf;
00025 double resolution;
00026 int counter;
00027 double zfilt_min;
00028 bool forceSIR;
00032 NDTMCL(double map_resolution, lslgeneric::NDTMap<PointT> &nd_map, double zfilter):
00033 map(new lslgeneric::LazyGrid<PointT>(map_resolution))
00034 {
00035 isInit = false;
00036 forceSIR = false;
00037 resolution=map_resolution;
00038 counter = 0;
00039 zfilt_min = zfilter;
00040 sinceSIR = 0;
00043 double cx,cy,cz;
00044 if(!nd_map.getCentroid(cx, cy, cz)){
00045 fprintf(stderr,"Centroid NOT Given-abort!\n");
00046 exit(1);
00047 }else{
00048 fprintf(stderr,"Centroid(%lf,%lf,%lf)\n",cx,cy,cz);
00049 }
00050
00051 double wx,wy,wz;
00052
00053 if(!nd_map.getGridSizeInMeters(wx, wy, wz)){
00054 fprintf(stderr,"Grid size NOT Given-abort!\n");
00055 exit(1);
00056 }else{
00057 fprintf(stderr,"GridSize(%lf,%lf,%lf)\n",wx,wy,wz);
00058 }
00059
00060 map.initialize(cx,cy,cz,wx,wy,wz);
00061
00062 std::vector<lslgeneric::NDTCell<PointT>*> ndts;
00063 ndts = nd_map.getAllCells();
00064 fprintf(stderr,"NDT MAP with %lu components",ndts.size());
00065 for(unsigned int i=0;i<ndts.size();i++){
00066 Eigen::Vector3d m = ndts[i]->getMean();
00067 if(m[2]>zfilter){
00068 Eigen::Matrix3d cov = ndts[i]->getCov();
00069 unsigned int nump = ndts[i]->getN();
00070
00071 map.addDistributionToCell(cov, m,nump);
00072 }
00073 }
00074 }
00075
00080 void initializeFilter(double x, double y, double yaw,double x_e, double y_e, double yaw_e, int numParticles){
00081 pf.initializeNormalRandom(mcl::pose(x,y,yaw), mcl::pose(x_e,y_e,yaw_e),numParticles);
00082 }
00083
00084 void updateAndPredict(Eigen::Affine3d Tmotion, pcl::PointCloud<PointT> &cloud){
00085 Eigen::Vector3d tr = Tmotion.translation();
00086 Eigen::Vector3d rot = Tmotion.rotation().eulerAngles(0,1,2);
00087
00088
00098 pf.predict(mcl::pose(tr[0],tr[1],rot[2]), mcl::pose(tr[0]*0.1 + 0.005,tr[1]*0.1+ 0.005,rot[2]*0.1+0.001));
00099
00100 lslgeneric::NDTMap<PointT> local_map(new lslgeneric::LazyGrid<PointT>(resolution));
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115 local_map.addPointCloudSimple(cloud);
00116
00117 local_map.computeNDTCells(CELL_UPDATE_MODE_STUDENT_T);
00118 int Nn = 0;
00119
00120 for(int i=0;i<pf.NumOfParticles;i++){
00121 Eigen::Affine3d T = getAsAffine(i);
00122
00123 std::vector<lslgeneric::NDTCell<PointT>*> ndts;
00124 ndts = local_map.pseudoTransformNDT(T);
00125 double score=1;
00126
00127 if(ndts.size()==0) fprintf(stderr,"ERROR no gaussians in measurement!!!\n");
00128 Nn = ndts.size();
00129 for(int n=0;n<ndts.size();n++){
00130 Eigen::Vector3d m = ndts[n]->getMean();
00131 if(m[2]<zfilt_min) continue;
00132
00133 lslgeneric::NDTCell<PointT> *cell;
00134 PointT p;
00135 p.x = m[0];p.y=m[1];p.z=m[2];
00136
00137
00138 if(map.getCellForPoint(p,cell)){
00139 if(cell == NULL) continue;
00140 if(cell->hasGaussian_){
00141 Eigen::Matrix3d covCombined = cell->getCov() + ndts[n]->getCov();
00142 Eigen::Matrix3d icov;
00143 bool exists;
00144 double det = 0;
00145 covCombined.computeInverseAndDetWithCheck(icov,det,exists);
00146 if(!exists) continue;
00147 double l = (cell->getMean() - m).dot(icov*(cell->getMean() - m));
00148 if(l*0 != 0) continue;
00149
00150 score += 0.1 + 0.9 * exp(-0.05*l/2.0);
00151 }else{
00152 }
00153 }
00154 }
00155
00156
00157
00158 pf.Particles[i].lik = score;
00159 for(unsigned int j=0;j<ndts.size();j++){
00160 delete ndts[j];
00161 }
00162
00163 }
00164
00165 pf.normalize();
00166
00167
00168 if(forceSIR){
00169
00170 fprintf(stderr, "forceSIR(%d) ",forceSIR);
00171 pf.SIRUpdate();
00172 }else{
00173
00174 double varP=0;
00175 for(int i = 0; i<pf.NumOfParticles;i++){
00176 varP += (pf.Particles[i].p - 1.0/pf.NumOfParticles)*(pf.Particles[i].p - 1.0/pf.NumOfParticles);
00177 }
00178 varP /= pf.NumOfParticles;
00179 varP = sqrt(varP);
00180 fprintf(stderr,"Var P=%lf (Npf=%d, Nm=%d)",varP,pf.NumOfParticles, Nn);
00181 if(varP > 0.006 || sinceSIR >25){
00182 fprintf(stderr,"-SIR- ");
00183 sinceSIR = 0;
00184 pf.SIRUpdate();
00185 }else{
00186 sinceSIR++;
00187 }
00188
00189 }
00190 }
00191
00192 Eigen::Vector3d getMean(){
00193 mcl::pose m = pf.getDistributionMean(true);
00194 Eigen::Vector3d mm; mm<<m.x,m.y,m.a;
00195 return mm;
00196 }
00197
00198
00199 private:
00200 bool isInit;
00201 int sinceSIR;
00202 Eigen::Affine3d getAsAffine(int i){
00203 Eigen::Matrix3d m;
00204 m = Eigen::AngleAxisd(0, Eigen::Vector3d::UnitX())
00205 * Eigen::AngleAxisd(0, Eigen::Vector3d::UnitY())
00206 * Eigen::AngleAxisd(pf.Particles[i].a, Eigen::Vector3d::UnitZ());
00207 Eigen::Translation3d v(pf.Particles[i].x,pf.Particles[i].y,0);
00208 Eigen::Affine3d T = v*m;
00209 return T;
00210 }
00211
00212 };
00213
00214 #endif
00215