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 template <typename PointT>
00101 class NDTMap
00102 {
00103 public:
00104     NDTMap()
00105     {
00106         index_ = NULL;
00107         guess_size_ = true;
00108     }
00113     NDTMap(SpatialIndex<PointT> *idx)
00114     {
00115 
00116         index_ = idx;
00117         //this is used to prevent memory de-allocation of the *si
00118         //si was allocated outside the NDT class and should be deallocated outside
00119         isFirstLoad_=true;
00120         map_sizex = -1.0;
00121         map_sizey = -1.0;
00122         map_sizez = -1.0;
00123         is3D = true;
00124                                 guess_size_ = true;
00125     }
00126 
00127     NDTMap(const NDTMap& other)
00128     {
00129         if(other.index_ != NULL)
00130         {
00131             this->index_ = other.index_->copy();
00132             isFirstLoad_ = false;
00133         }
00134     }
00135 
00142     NDTMap(SpatialIndex<PointT> *idx, float cenx, float ceny, float cenz, float sizex, float sizey, float sizez)
00143     {
00144         if(idx == NULL)
00145         {
00146             fprintf(stderr,"Idx == NULL - abort()\n");
00147             exit(1);
00148         }
00149         index_ = idx;
00150 
00151         //this is used to prevent memory de-allocation of the *si
00152         //si was allocated outside the NDT class and should be deallocated outside
00153         isFirstLoad_=false;
00154 
00155         NDTCell<PointT> *ptCell = new NDTCell<PointT>();
00156         index_->setCellType(ptCell);
00157         delete ptCell;
00158         index_->setCenter(cenx,ceny,cenz);
00159         index_->setSize(sizex,sizey,sizez);
00160         map_sizex = sizex;
00161         map_sizey = sizey;
00162         map_sizez = sizez;
00163         is3D=true;
00164         LazyGrid<PointT> *lz = dynamic_cast<LazyGrid<PointT>*>(index_);
00165         if(lz == NULL)
00166         {
00167             fprintf(stderr,"Unfortunately This constructor works only with Lazygrid!\n");
00168             exit(1);
00169         }
00170         lz->initializeAll();
00171                                 guess_size_ = false;
00172     }
00173 
00178     void initialize(double cenx, double ceny, double cenz, double sizex, double sizey, double sizez)
00179     {
00180         isFirstLoad_=false;
00181 
00182         NDTCell<PointT> *ptCell = new NDTCell<PointT>();
00183         index_->setCellType(ptCell);
00184         delete ptCell;
00185         index_->setCenter(cenx,ceny,cenz);
00186         index_->setSize(sizex,sizey,sizez);
00187         map_sizex = sizex;
00188         map_sizey = sizey;
00189         map_sizez = sizez;
00190         is3D=true;
00191         LazyGrid<PointT> *lz = dynamic_cast<LazyGrid<PointT>*>(index_);
00192         if(lz == NULL)
00193         {
00194             fprintf(stderr,"Unfortunately This constructor works only with Lazygrid!\n");
00195             exit(1);
00196         }
00197         lz->initializeAll();
00198                                 guess_size_ = false;
00199     }
00200 
00201 
00202 
00206     virtual ~NDTMap()
00207     {
00208         //std::cout<<"DELETE MAP\n";
00209         if(index_ !=NULL && !isFirstLoad_)
00210         {
00211             //std::cout<<"DELETE INDEX\n";
00212             delete index_;
00213                                                 index_ = NULL;
00214         }
00215         
00216     }
00217 
00218     void setMode(bool is3D_)
00219     {
00220         is3D=is3D_;
00221     }
00222 
00227     void setMapSize(float sx, float sy, float sz)
00228     {
00229         map_sizex = sx;
00230         map_sizey = sy;
00231         map_sizez = sz;
00232     }
00233 
00234 
00246     virtual void addPointCloud(const Eigen::Vector3d &origin, const pcl::PointCloud<PointT> &pc, double classifierTh=0.06, 
00247                                                                                                                                 double maxz = 100.0, double sensor_noise = 0.25, double occupancy_limit = 255);
00248 
00252     void addPointCloudSimple(const pcl::PointCloud<PointT> &pc,double maxz=100.0);
00253 
00254 
00270     virtual void addPointCloudMeanUpdate(const Eigen::Vector3d &origin, 
00271             const pcl::PointCloud<PointT> &pc, 
00272             const Eigen::Vector3d &localmapsize,
00273             unsigned int maxnumpoints = 1e9, float occupancy_limit=255 ,double maxz = 100.0, double sensor_noise = 0.25);
00274 
00280     virtual bool addMeasurement(const Eigen::Vector3d &origin,PointT endpoint, double classifierTh, double maxz, double sensor_noise);
00281 
00282 
00291     void addDistributionToCell(const Eigen::Matrix3d &ucov,const Eigen::Vector3d &umean, unsigned int numpointsindistribution, 
00292                                                                                                                         float r=0, float g=0,float b=0, unsigned int maxnumpoints=1e9, float max_occupancy=1024);
00293 
00294 
00304     virtual void loadPointCloud(const pcl::PointCloud<PointT> &pc, double range_limit = -1);
00306 
00307 
00309 
00315     void loadPointCloud(const pcl::PointCloud<PointT> &pc, const std::vector<std::vector<size_t> > &indices);
00316 
00327     void loadPointCloudCentroid(const pcl::PointCloud<PointT> &pc, const Eigen::Vector3d &origin, const Eigen::Vector3d &old_centroid, const Eigen::Vector3d &map_size, double range_limit);
00328                 
00329                 
00330     void loadDepthImage(const cv::Mat& depthImage, DepthCamera<PointT> &cameraParams);
00331     pcl::PointCloud<PointT> loadDepthImageFeatures(const cv::Mat& depthImage, std::vector<cv::KeyPoint> &keypoints,
00332             size_t &supportSize, double maxVar, DepthCamera<PointT> &cameraParams, bool estimateParamsDI=false, bool nonMean = false);
00333 
00339     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);
00340 
00344     void computeNDTCellsSimple();
00348     void writeToVRML(const char* filename);
00349     virtual void writeToVRML(FILE* fout);
00350     virtual void writeToVRML(FILE* fout, Eigen::Vector3d col);
00351 
00352     int writeToJFF(const char* filename);
00353     int writeLazyGridJFF(FILE * jffout);
00354     int writeCellVectorJFF(FILE * jffout);
00355     int writeOctTreeJFF(FILE * jffout);
00356 
00357     int loadFromJFF(const char* filename);
00358 
00359     inline SpatialIndex<PointT>* getMyIndex() const
00360     {
00361         return index_;
00362     }
00364     std::string getMyIndexStr() const;
00366     int getMyIndexInt() const;
00367 
00368     //computes the likelihood of a single observation
00369     virtual double getLikelihoodForPoint(PointT pt);
00370 
00372     virtual bool getCellAtPoint(const PointT &refPoint, NDTCell<PointT> *&cell);
00373 
00378     virtual bool getCellForPoint(const PointT &refPoint, NDTCell<PointT> *&cell, bool checkForGaussian=true) const;
00383     virtual std::vector<NDTCell<PointT>*> getCellsForPoint(const PointT pt, int n_neighbours, bool checkForGaussian=true) const;
00387     virtual std::vector<NDTCell<PointT>*> getInitializedCellsForPoint(const PointT pt) const;
00388 
00389 
00391     NDTCell<PointT>* getCellIdx(unsigned int idx) const;
00392 
00396     virtual std::vector<NDTCell<PointT>*> pseudoTransformNDT(Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> T);
00397 
00401     NDTMap<PointT>* pseudoTransformNDTMap(Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> T);
00406     virtual std::vector<lslgeneric::NDTCell<PointT>*> getAllCells() const;
00407 
00412     virtual std::vector<lslgeneric::NDTCell<PointT>*> getAllInitializedCells();
00413 
00414 
00415     int numberOfActiveCells();
00416 
00417     virtual bool getCentroid(double &cx, double &cy, double &cz)
00418     {
00419         LazyGrid<PointT> *lz = dynamic_cast<LazyGrid<PointT>*>(index_);
00420         if(lz == NULL) return false;
00421         lz->getCenter(cx, cy, cz);
00422         return true;
00423     }
00424     bool getGridSizeInMeters(double &cx, double &cy, double &cz)
00425     {
00426         LazyGrid<PointT> *lz = dynamic_cast<LazyGrid<PointT>*>(index_);
00427         if(lz == NULL) return false;
00428         lz->getGridSizeInMeters(cx, cy, cz);
00429         return true;
00430     }
00434     void guessSize(float cenx, float ceny, float cenz, float sizex, float sizey, float sizez) {
00435                         guess_size_ = true;
00436                         centerx=cenx;
00437                         centery=ceny;
00438                         centerz=cenz;
00439                         map_sizex=sizex;
00440                         map_sizey=sizey;
00441                         map_sizez=sizez;
00442     }
00443 
00444     //tsv: temporary debug function
00445     void debugToVRML(const char* fname, pcl::PointCloud<PointT> &pc);
00446     
00450     double getDepth(Eigen::Vector3d origin, Eigen::Vector3d dir, double maxDepth=100);
00451     double getDepthSmooth(Eigen::Vector3d origin,
00452                           Eigen::Vector3d dir,
00453                           double maxDepth = 20,
00454                           int n_neigh = 1,
00455                           double weight = 5.0,
00456                           double threshold = 0.2,
00457                           Eigen::Vector3d *hit = NULL);
00458     
00459 protected:
00460     bool is3D;
00461     SpatialIndex<PointT> *index_;
00462     bool isFirstLoad_;
00463     float map_sizex;
00464     float map_sizey;
00465     float map_sizez;
00466     float centerx,centery,centerz;
00467     bool guess_size_;
00468     std::set<NDTCell<PointT>*> update_set;
00469 
00470 public:
00471     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00472     pcl::PointCloud<PointT> conflictPoints; 
00473 
00474 
00475 };
00476 
00477 } // end namespace
00478 
00479 #include <ndt_map/impl/ndt_map.hpp>
00480 
00481 #endif


ndt_map
Author(s): Todor Stoyanov, Jari Saarinen, Henrik Andreasson
autogenerated on Mon Oct 6 2014 03:18:54