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 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
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
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
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
00145 Cell<PointT> *protoType;
00146 std::vector<Cell<PointT>*> activeCells;
00147
00148 bool centerIsSet, sizeIsSet;
00149
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
00158 };
00159
00160
00161 };
00162 #include<ndt_map/impl/lazy_grid.hpp>
00163
00164 #endif