lazy_grid.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 LSL_LAZZY_GRID_HH
00036 #define LSL_LAZZY_GRID_HH
00037 
00038 #include <ndt_map/spatial_index.h>
00039 #include <ndt_map/ndt_cell.h>
00040 
00041 namespace lslgeneric
00042 {
00043 
00047 class LazyGrid : public SpatialIndex
00048 {
00049 public:
00050     LazyGrid(double cellSize);
00051     LazyGrid(LazyGrid *prot);
00052     LazyGrid(double sizeXmeters, double sizeYmeters, double sizeZmeters,
00053              double cellSizeX, double cellSizeY, double cellSizeZ,
00054              double _centerX, double _centerY, double _centerZ,
00055              NDTCell *cellPrototype );
00056     virtual ~LazyGrid();
00057 
00058     virtual NDTCell* getCellForPoint(const pcl::PointXYZ &point);
00059     virtual NDTCell* addPoint(const pcl::PointXYZ &point);
00060 
00061     //these two don't make much sense...
00063     virtual typename SpatialIndex::CellVectorItr begin();
00065     virtual typename SpatialIndex::CellVectorItr end();
00066     virtual int size();
00067 
00069     virtual SpatialIndex* clone() const;
00070     virtual SpatialIndex* copy() const;
00071 
00073     virtual void getNeighbors(const pcl::PointXYZ &point, const double &radius, std::vector<NDTCell*> &cells);
00074 
00076     virtual void setCellType(NDTCell *type);
00077 
00078     virtual void setCenter(const double &cx, const double &cy, const double &cz);
00079     virtual void setSize(const double &sx, const double &sy, const double &sz);
00080 
00081     virtual NDTCell* getClosestNDTCell(const pcl::PointXYZ &pt, bool checkForGaussian=true);
00082     virtual std::vector<NDTCell*> getClosestNDTCells(const pcl::PointXYZ &pt, int &n_neigh, bool checkForGaussian=true);
00083     virtual std::vector<NDTCell*> getClosestCells(const pcl::PointXYZ &pt);
00084 
00085     virtual inline void getCellAt(int indX, int indY, int indZ, NDTCell* &cell){
00086         if(indX < sizeX && indY < sizeY && indZ < sizeZ && indX >=0 && indY >=0 && indZ >=0){
00087             cell = dataArray[indX][indY][indZ];
00088         }else{
00089                 cell = NULL;
00090                 
00091         }
00092     }
00093     virtual inline void getCellAt(const pcl::PointXYZ& pt, NDTCell* &cell){
00094         int indX,indY,indZ;
00095         this->getIndexForPoint(pt,indX,indY,indZ);
00096         this->getCellAt(indX,indY,indZ,cell);
00097     }
00098     //FIXME: these two are now not needed anymore
00099     virtual inline void getNDTCellAt(int indX, int indY, int indZ, NDTCell* &cell){
00100                         if(indX < sizeX && indY < sizeY && indZ < sizeZ && indX >=0 && indY >=0 && indZ >=0){
00101                                         cell = (dataArray[indX][indY][indZ]);
00102                         }else{
00103                                 cell = NULL;
00104                         }
00105     }
00106     virtual inline void getNDTCellAt(const pcl::PointXYZ& pt, NDTCell* &cell){
00107                         int indX,indY,indZ;
00108                         this->getIndexForPoint(pt,indX,indY,indZ);
00109                         this->getNDTCellAt(indX,indY,indZ,cell);
00110     }
00111 
00112     void getCellSize(double &cx, double &cy, double &cz);
00113     void getGridSize(int &cx, int &cy, int &cz);
00114     void getGridSizeInMeters(double &cx, double &cy, double &cz);
00115     void getCenter(double &cx, double &cy, double &cz);
00116     virtual void getIndexForPoint(const pcl::PointXYZ& pt, int &idx, int &idy, int &idz);
00117     NDTCell* getProtoType()
00118     {
00119         return protoType;
00120     }
00121 
00122     virtual void initialize();
00123     virtual void initializeAll() ;
00124 
00125     NDTCell ****getDataArrayPtr()
00126     {
00127         return dataArray;
00128     }
00129 
00131     virtual int loadFromJFF(FILE * jffin);
00132     bool traceLine(const Eigen::Vector3d &origin, const pcl::PointXYZ &endpoint, const Eigen::Vector3d &diff, const double& maxz, std::vector<NDTCell*> &cells);
00133     bool traceLineWithEndpoint(const Eigen::Vector3d &origin, const pcl::PointXYZ &endpoint, const Eigen::Vector3d &diff, const double& maxz, std::vector<NDTCell*> &cells, Eigen::Vector3d &final_point);
00134     bool isInside(const pcl::PointXYZ& pt) {
00135                         int indX,indY,indZ;
00136                         this->getIndexForPoint(pt,indX,indY,indZ);
00137                         return(indX < sizeX && indY < sizeY && indZ < sizeZ && indX >=0 && indY >=0 && indZ >=0);
00138     }
00139 protected:
00140     bool initialized;
00141     NDTCell ****dataArray;
00142     //bool ***linkedCells;
00143     NDTCell *protoType;
00144     std::vector<NDTCell*> activeCells;
00145     bool centerIsSet, sizeIsSet;
00146 
00147     double sizeXmeters, sizeYmeters, sizeZmeters;
00148     double cellSizeX, cellSizeY, cellSizeZ;
00149     double centerX, centerY, centerZ;
00150     int sizeX,sizeY,sizeZ;
00151 
00152     virtual bool checkCellforNDT(int indX, int indY, int indZ, bool checkForGaussian=true);
00153 public:
00154     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00155 };
00156 
00157 
00158 }; //end namespace
00159 //#include<ndt_map/impl/lazy_grid.hpp>
00160 
00161 #endif


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