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_MAP_HH
00036 #define NDT_MAP_HH
00037
00038 #include <spatial_index.h>
00039 #include <ndt_cell.h>
00040 #include <depth_camera.h>
00041 #include <set>
00042
00043 #include <cstdlib>
00044 #include <lazy_grid.h>
00045 #include <cv.h>
00046 #include <pcl/point_cloud.h>
00047 #include <pcl/point_types.h>
00048
00049
00050 namespace lslgeneric
00051 {
00052
00099 template <typename PointT>
00100 class NDTMap
00101 {
00102 public:
00103 NDTMap()
00104 {
00105 index_ = NULL;
00106 guess_size_ = true;
00107 }
00112 NDTMap(SpatialIndex<PointT> *idx)
00113 {
00114
00115 index_ = idx;
00116
00117
00118 isFirstLoad_=true;
00119 map_sizex = -1.0;
00120 map_sizey = -1.0;
00121 map_sizez = -1.0;
00122 is3D = true;
00123 guess_size_ = true;
00124 }
00125
00126 NDTMap(const NDTMap& other)
00127 {
00128 if(other.index_ != NULL)
00129 {
00130 this->index_ = other.index_->copy();
00131 isFirstLoad_ = false;
00132 }
00133 }
00134
00141 NDTMap(SpatialIndex<PointT> *idx, float cenx, float ceny, float cenz, float sizex, float sizey, float sizez)
00142 {
00143 if(idx == NULL)
00144 {
00145 fprintf(stderr,"Idx == NULL - abort()\n");
00146 exit(1);
00147 }
00148 index_ = idx;
00149
00150
00151
00152 isFirstLoad_=false;
00153
00154 NDTCell<PointT> *ptCell = new NDTCell<PointT>();
00155 index_->setCellType(ptCell);
00156 delete ptCell;
00157 index_->setCenter(cenx,ceny,cenz);
00158 index_->setSize(sizex,sizey,sizez);
00159 map_sizex = sizex;
00160 map_sizey = sizey;
00161 map_sizez = sizez;
00162 is3D=true;
00163 LazyGrid<PointT> *lz = dynamic_cast<LazyGrid<PointT>*>(index_);
00164 if(lz == NULL)
00165 {
00166 fprintf(stderr,"Unfortunately This constructor works only with Lazygrid!\n");
00167 exit(1);
00168 }
00169 lz->initializeAll();
00170 guess_size_ = false;
00171 }
00172
00177 void initialize(double cenx, double ceny, double cenz, double sizex, double sizey, double sizez)
00178 {
00179 isFirstLoad_=false;
00180
00181 NDTCell<PointT> *ptCell = new NDTCell<PointT>();
00182 index_->setCellType(ptCell);
00183 delete ptCell;
00184 index_->setCenter(cenx,ceny,cenz);
00185 index_->setSize(sizex,sizey,sizez);
00186 map_sizex = sizex;
00187 map_sizey = sizey;
00188 map_sizez = sizez;
00189 is3D=true;
00190 LazyGrid<PointT> *lz = dynamic_cast<LazyGrid<PointT>*>(index_);
00191 if(lz == NULL)
00192 {
00193 fprintf(stderr,"Unfortunately This constructor works only with Lazygrid!\n");
00194 exit(1);
00195 }
00196 lz->initializeAll();
00197 guess_size_ = false;
00198 }
00199
00200
00201
00205 virtual ~NDTMap()
00206 {
00207
00208 if(index_ !=NULL && !isFirstLoad_)
00209 {
00210
00211 delete index_;
00212 index_ = NULL;
00213 }
00214
00215 }
00216
00217 void setMode(bool is3D_)
00218 {
00219 is3D=is3D_;
00220 }
00221
00226 void setMapSize(float sx, float sy, float sz)
00227 {
00228 map_sizex = sx;
00229 map_sizey = sy;
00230 map_sizez = sz;
00231 }
00232
00233
00245 virtual void addPointCloud(const Eigen::Vector3d &origin, const pcl::PointCloud<PointT> &pc, double classifierTh=0.06,
00246 double maxz = 100.0, double sensor_noise = 0.25, double occupancy_limit = 255);
00247
00251 void addPointCloudSimple(const pcl::PointCloud<PointT> &pc,double maxz=100.0);
00252
00253
00269 virtual void addPointCloudMeanUpdate(const Eigen::Vector3d &origin,
00270 const pcl::PointCloud<PointT> &pc,
00271 const Eigen::Vector3d &localmapsize,
00272 unsigned int maxnumpoints = 1e9, float occupancy_limit=255 ,double maxz = 100.0, double sensor_noise = 0.25);
00273
00279 virtual bool addMeasurement(const Eigen::Vector3d &origin,PointT endpoint, double classifierTh, double maxz, double sensor_noise);
00280
00281
00290 void addDistributionToCell(const Eigen::Matrix3d &ucov,const Eigen::Vector3d &umean, unsigned int numpointsindistribution,
00291 float r=0, float g=0,float b=0, unsigned int maxnumpoints=1e9, float max_occupancy=1024);
00292
00293
00303 virtual void loadPointCloud(const pcl::PointCloud<PointT> &pc, double range_limit = -1);
00305
00306
00308
00314 void loadPointCloud(const pcl::PointCloud<PointT> &pc, const std::vector<std::vector<size_t> > &indices);
00315
00326 void loadPointCloudCentroid(const pcl::PointCloud<PointT> &pc, const Eigen::Vector3d &origin, const Eigen::Vector3d &old_centroid, const Eigen::Vector3d &map_size, double range_limit);
00327
00328
00329 void loadDepthImage(const cv::Mat& depthImage, DepthCamera<PointT> &cameraParams);
00330 pcl::PointCloud<PointT> loadDepthImageFeatures(const cv::Mat& depthImage, std::vector<cv::KeyPoint> &keypoints,
00331 size_t &supportSize, double maxVar, DepthCamera<PointT> &cameraParams, bool estimateParamsDI=false, bool nonMean = false);
00332
00338 virtual void computeNDTCells(int cellupdatemode = CELL_UPDATE_MODE_SAMPLE_VARIANCE, unsigned int maxnumpoints = 1e9, float occupancy_limit=255, Eigen::Vector3d origin = Eigen::Vector3d(0,0,0), double sensor_noise=0.1);
00339
00343 void computeNDTCellsSimple();
00347 void writeToVRML(const char* filename);
00348 virtual void writeToVRML(FILE* fout);
00349 virtual void writeToVRML(FILE* fout, Eigen::Vector3d col);
00350
00351 int writeToJFF(const char* filename);
00352 int writeLazyGridJFF(FILE * jffout);
00353 int writeCellVectorJFF(FILE * jffout);
00354 int writeOctTreeJFF(FILE * jffout);
00355
00356 int loadFromJFF(const char* filename);
00357
00358 inline SpatialIndex<PointT>* getMyIndex() const
00359 {
00360 return index_;
00361 }
00363 std::string getMyIndexStr() const;
00365 int getMyIndexInt() const;
00366
00367
00368 virtual double getLikelihoodForPoint(PointT pt);
00369
00371 virtual bool getCellAtPoint(const PointT &refPoint, NDTCell<PointT> *&cell);
00372
00377 virtual bool getCellForPoint(const PointT &refPoint, NDTCell<PointT> *&cell, bool checkForGaussian=true) const;
00382 virtual std::vector<NDTCell<PointT>*> getCellsForPoint(const PointT pt, int n_neighbours, bool checkForGaussian=true) const;
00386 virtual std::vector<NDTCell<PointT>*> getInitializedCellsForPoint(const PointT pt) const;
00387
00388
00390 NDTCell<PointT>* getCellIdx(unsigned int idx) const;
00391
00395 virtual std::vector<NDTCell<PointT>*> pseudoTransformNDT(Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> T);
00396
00400 NDTMap<PointT>* pseudoTransformNDTMap(Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> T);
00405 virtual std::vector<lslgeneric::NDTCell<PointT>*> getAllCells() const;
00406
00411 virtual std::vector<lslgeneric::NDTCell<PointT>*> getAllInitializedCells();
00412
00413
00414 int numberOfActiveCells();
00415
00416 virtual bool getCentroid(double &cx, double &cy, double &cz)
00417 {
00418 LazyGrid<PointT> *lz = dynamic_cast<LazyGrid<PointT>*>(index_);
00419 if(lz == NULL) return false;
00420 lz->getCenter(cx, cy, cz);
00421 return true;
00422 }
00423 bool getGridSizeInMeters(double &cx, double &cy, double &cz)
00424 {
00425 LazyGrid<PointT> *lz = dynamic_cast<LazyGrid<PointT>*>(index_);
00426 if(lz == NULL) return false;
00427 lz->getGridSizeInMeters(cx, cy, cz);
00428 return true;
00429 }
00433 void guessSize(float cenx, float ceny, float cenz, float sizex, float sizey, float sizez) {
00434 guess_size_ = true;
00435 centerx=cenx;
00436 centery=ceny;
00437 centerz=cenz;
00438 map_sizex=sizex;
00439 map_sizey=sizey;
00440 map_sizez=sizez;
00441 }
00442
00443
00444 void debugToVRML(const char* fname, pcl::PointCloud<PointT> &pc);
00445
00449 double getDepth(Eigen::Vector3d origin, Eigen::Vector3d dir, double maxDepth=100);
00450 double getDepthSmooth(Eigen::Vector3d origin,
00451 Eigen::Vector3d dir,
00452 double maxDepth = 20,
00453 int n_neigh = 1,
00454 double weight = 5.0,
00455 double threshold = 0.2,
00456 Eigen::Vector3d *hit = NULL);
00457
00458 protected:
00459 bool is3D;
00460 SpatialIndex<PointT> *index_;
00461 bool isFirstLoad_;
00462 float map_sizex;
00463 float map_sizey;
00464 float map_sizez;
00465 float centerx,centery,centerz;
00466 bool guess_size_;
00467 std::set<NDTCell<PointT>*> update_set;
00468
00469 public:
00470 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00471 pcl::PointCloud<PointT> conflictPoints;
00472
00473
00474 };
00475
00476 }
00477
00478 #include <impl/ndt_map.hpp>
00479
00480 #endif