ndt_map.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, AASS Research Center, Orebro University.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of AASS Research Center nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  */
00035 #ifndef NDT_MAP_HH
00036 #define NDT_MAP_HH
00037 
00038 #include <ndt_map/spatial_index.h>
00039 #include <ndt_map/ndt_cell.h>
00040 #include <ndt_map/depth_camera.h>
00041 #include <ndt_map/lazy_grid.h>
00042 
00043 #include <set>
00044 #include <cstdlib>
00045 
00046 #include <cv.h>
00047 #include <pcl/point_cloud.h>
00048 #include <pcl/point_types.h>
00049 
00050 
00051 namespace lslgeneric
00052 {
00053 
00100 class NDTMap
00101 {
00102 public:
00103     NDTMap()
00104     {
00105         index_ = NULL;
00106         guess_size_ = true;
00107     }
00112     NDTMap(SpatialIndex *idx)
00113     {
00114 
00115         index_ = idx;
00116         //this is used to prevent memory de-allocation of the *si
00117         //si was allocated outside the NDT class and should be deallocated outside
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 *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         //this is used to prevent memory de-allocation of the *si
00151         //si was allocated outside the NDT class and should be deallocated outside
00152         isFirstLoad_=false;
00153 
00154         NDTCell *ptCell = new NDTCell();
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 *lz = dynamic_cast<LazyGrid*>(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 *ptCell = new NDTCell();
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 *lz = dynamic_cast<LazyGrid*>(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         //std::cout<<"DELETE MAP\n";
00208         if(index_ !=NULL && !isFirstLoad_)
00209         {
00210             //std::cout<<"DELETE INDEX\n";
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<pcl::PointXYZ> &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<pcl::PointXYZ> &pc,double maxz=100.0);
00252 
00253 
00269     virtual void addPointCloudMeanUpdate(const Eigen::Vector3d &origin, 
00270             const pcl::PointCloud<pcl::PointXYZ> &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,pcl::PointXYZ 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<pcl::PointXYZ> &pc, double range_limit = -1);
00305 
00306 
00308 
00314     void loadPointCloud(const pcl::PointCloud<pcl::PointXYZ> &pc, const std::vector<std::vector<size_t> > &indices);
00315 
00326     void loadPointCloudCentroid(const pcl::PointCloud<pcl::PointXYZ> &pc, const Eigen::Vector3d &origin, const Eigen::Vector3d &old_centroid, const Eigen::Vector3d &map_size, double range_limit);
00327                 
00328     void loadDepthImage(const cv::Mat& depthImage, DepthCamera<pcl::PointXYZ> &cameraParams);
00329     pcl::PointCloud<pcl::PointXYZ> loadDepthImageFeatures(const cv::Mat& depthImage, std::vector<cv::KeyPoint> &keypoints,
00330             size_t &supportSize, double maxVar, DepthCamera<pcl::PointXYZ> &cameraParams, bool estimateParamsDI=false, bool nonMean = false);
00331 
00337     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);
00338 
00342     void computeNDTCellsSimple();
00347     int writeToJFF(const char* filename);
00348     int writeLazyGridJFF(FILE * jffout);
00349     int writeCellVectorJFF(FILE * jffout);
00350     int writeOctTreeJFF(FILE * jffout);
00351 
00352     int loadFromJFF(const char* filename);
00353 
00354     inline SpatialIndex* getMyIndex() const
00355     {
00356         return index_;
00357     }
00359     std::string getMyIndexStr() const;
00361     int getMyIndexInt() const;
00362 
00363     //computes the likelihood of a single observation
00364     virtual double getLikelihoodForPoint(pcl::PointXYZ pt);
00365 
00367     virtual bool getCellAtPoint(const pcl::PointXYZ &refPoint, NDTCell *&cell);
00368 
00373     virtual bool getCellForPoint(const pcl::PointXYZ &refPoint, NDTCell *&cell, bool checkForGaussian=true) const;
00378     virtual std::vector<NDTCell*> getCellsForPoint(const pcl::PointXYZ pt, int n_neighbours, bool checkForGaussian=true) const;
00382     virtual std::vector<NDTCell*> getInitializedCellsForPoint(const pcl::PointXYZ pt) const;
00383 
00384 
00386     NDTCell* getCellIdx(unsigned int idx) const;
00387 
00391     virtual std::vector<NDTCell*> pseudoTransformNDT(Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> T);
00392 
00396     NDTMap* pseudoTransformNDTMap(Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> T);
00401     virtual std::vector<lslgeneric::NDTCell*> getAllCells() const;
00402 
00407     virtual std::vector<lslgeneric::NDTCell*> getAllInitializedCells();
00408 
00409 
00410     int numberOfActiveCells();
00411 
00412     virtual bool getCentroid(double &cx, double &cy, double &cz)
00413     {
00414       LazyGrid *lz = dynamic_cast<LazyGrid*>(index_);
00415       if(lz == NULL) return false;
00416       lz->getCenter(cx, cy, cz);
00417       return true;
00418     }
00419     bool getGridSize(int &cx, int &cy, int &cz)
00420     {
00421       LazyGrid *lz = dynamic_cast<LazyGrid*>(index_);
00422       if(lz == NULL) return false;
00423       lz->getGridSize(cx, cy, cz);
00424       return true;
00425     }
00426 
00427     bool getGridSizeInMeters(double &cx, double &cy, double &cz)
00428     {
00429         LazyGrid *lz = dynamic_cast<LazyGrid*>(index_);
00430         if(lz == NULL) return false;
00431         lz->getGridSizeInMeters(cx, cy, cz);
00432         return true;
00433     }
00434     bool getCellSizeInMeters(double &cx, double &cy, double &cz)
00435     {
00436         LazyGrid *lz = dynamic_cast<LazyGrid*>(index_);
00437         if(lz == NULL) return false;
00438         lz->getCellSize(cx, cy, cz);
00439         return true;
00440     }
00444     void guessSize(float cenx, float ceny, float cenz, float sizex, float sizey, float sizez) {
00445                         guess_size_ = true;
00446                         centerx=cenx;
00447                         centery=ceny;
00448                         centerz=cenz;
00449                         map_sizex=sizex;
00450                         map_sizey=sizey;
00451                         map_sizez=sizez;
00452     }
00453 
00457     double getDepth(Eigen::Vector3d origin, Eigen::Vector3d dir, double maxDepth=100);
00458     double getDepthSmooth(Eigen::Vector3d origin,
00459                           Eigen::Vector3d dir,
00460                           double maxDepth = 20,
00461                           int n_neigh = 1,
00462                           double weight = 5.0,
00463                           double threshold = 0.2,
00464                           Eigen::Vector3d *hit = NULL);
00465     
00466 protected:
00467     bool is3D;
00468     SpatialIndex *index_;
00469     bool isFirstLoad_;
00470     float map_sizex;
00471     float map_sizey;
00472     float map_sizez;
00473     float centerx,centery,centerz;
00474     bool guess_size_;
00475     std::set<NDTCell*> update_set;
00476 
00477 public:
00478     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00479     pcl::PointCloud<pcl::PointXYZ> conflictPoints; 
00480 
00481 
00482 };
00483 
00484 } // end namespace
00485 
00486 //#include <ndt_map/impl/ndt_map.hpp>
00487 
00488 #endif


ndt_map
Author(s): Todor Stoyanov, Jari Saarinen, Henrik Andreasson
autogenerated on Wed Aug 26 2015 15:24:40