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
00037
00038
00039
00040
00041
00055 #ifndef NDT_MAP_MATCHER_D2D_2D_HH
00056 #define NDT_MAP_MATCHER_D2D_2D_HH
00057
00058 #include "ndt_map.h"
00059 #include <ndt_matcher_d2d_2d.h>
00060 #include "pcl/point_cloud.h"
00061 #include "Eigen/Core"
00062
00063 #include <stdlib.h>
00064 #include <stdio.h>
00065 #include <math.h>
00066
00067
00068 namespace lslgeneric{
00069
00070 template <typename PointT>
00071 class NDTMapMatcherD2D_2D{
00072 public:
00073 lslgeneric::NDTMap<PointT> map;
00074
00082 NDTMapMatcherD2D_2D(double map_resolution, lslgeneric::NDTMap<PointT> &nd_map ,double miniz = 0.0, double maxiz = 0.0) :
00083 map(new lslgeneric::LazyGrid<PointT>(map_resolution))
00084 {
00085 isInit = false;
00086 resolution = map_resolution;
00087 min_z = miniz;
00088 max_z = maxiz;
00089 sensor_pose.setIdentity();
00092 double cx,cy,cz;
00093 if(!nd_map.getCentroid(cx, cy, cz)){
00094 fprintf(stderr,"Centroid NOT Given-abort!\n");
00095 exit(1);
00096 }else{
00097 fprintf(stderr,"Centroid(%lf,%lf,%lf)\n",cx,cy,cz);
00098 }
00099
00100 double wx,wy,wz;
00101
00102 if(!nd_map.getGridSizeInMeters(wx, wy, wz)){
00103 fprintf(stderr,"Grid size NOT Given-abort!\n");
00104 exit(1);
00105 }else{
00106 fprintf(stderr,"GridSize(%lf,%lf,%lf)\n",wx,wy,wz);
00107 }
00108
00109 map.initialize(cx,cy,cz,wx,wy,wz);
00110
00111 std::vector<lslgeneric::NDTCell<PointT>*> ndts;
00112 ndts = nd_map.getAllCells();
00113 fprintf(stderr,"NDTMapMatcherD2D_2D::Inserting %d gaussians to map\n",ndts.size());
00114 for(unsigned int i=0;i<ndts.size();i++){
00115 Eigen::Vector3d m = ndts[i]->getMean();
00116 if(m[2]>min_z && m[2] < max_z){
00117 Eigen::Matrix3d cov = ndts[i]->getCov();
00118 unsigned int nump = ndts[i]->getN();
00119 map.addDistributionToCell(cov, m,nump);
00120 }
00121 }
00122 }
00127 void setSensorPose(Eigen::Affine3d spose){
00128 sensor_pose = spose;
00129 }
00130
00137 bool update(Eigen::Affine3d Tinit, pcl::PointCloud<PointT> &cloud){
00139 lslgeneric::transformPointCloudInPlace(sensor_pose, cloud);
00140 pcl::PointCloud<PointT> cloud_tmp;
00142 for(unsigned int i=0;i<cloud.size();i++){
00143 bool add = true;
00144 if(cloud.points[i].z > max_z || cloud.points[i].z<min_z){
00145 add=false;
00146 }
00147 if(add) cloud_tmp.push_back(cloud.points[i]);
00148 }
00149 cloud = cloud_tmp;
00150
00152 lslgeneric::NDTMap<PointT> ndlocal(new lslgeneric::LazyGrid<PointT>(resolution));
00153 ndlocal.addPointCloudSimple(cloud);
00154 ndlocal.computeNDTCells(CELL_UPDATE_MODE_SAMPLE_VARIANCE);
00155
00156 lslgeneric::NDTMatcherD2D_2D<PointT,PointT> matcher;
00157 return(matcher.match( map, ndlocal,Tinit,true));
00158 }
00159
00163 bool updateNoFilt(Eigen::Affine3d &Tinit, pcl::PointCloud<PointT> &cloud){
00164
00166 lslgeneric::NDTMap<PointT> ndlocal(new lslgeneric::LazyGrid<PointT>(resolution));
00167 ndlocal.addPointCloudSimple(cloud);
00168 ndlocal.computeNDTCells(CELL_UPDATE_MODE_SAMPLE_VARIANCE);
00169
00170 lslgeneric::NDTMatcherD2D_2D<PointT,PointT> matcher;
00171 return matcher.match( map, ndlocal,Tinit,true);
00172 }
00173
00174 private:
00175 bool isInit;
00176
00177 double resolution;
00178 double min_z;
00179 double max_z;
00180
00181 Eigen::Affine3d sensor_pose;
00182
00183
00184 };
00185 }
00186 #endif