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


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