cell_vector.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_CELL_VECTOR_HH
00036 #define LSL_CELL_VECTOR_HH
00037 
00038 #include <ndt_map/spatial_index.h>
00039 #include <ndt_map/ndt_cell.h>
00040 #include <pcl/kdtree/impl/kdtree_flann.hpp>
00041 #include <pcl/console/print.h>
00042 
00043 namespace lslgeneric
00044 {
00045 
00049 class CellVector : public SpatialIndex
00050 {
00051 public:
00052     CellVector();
00053     CellVector(NDTCell* cellPrototype);
00054     CellVector(const CellVector& other);
00055     virtual ~CellVector();
00056 
00057     virtual NDTCell* getCellForPoint(const pcl::PointXYZ &point);
00058     virtual NDTCell* addPoint(const pcl::PointXYZ &point);
00059     void addCellPoints(pcl::PointCloud<pcl::PointXYZ> pc, const std::vector<size_t> &indices);
00060     
00061     void addCell(NDTCell* cell);
00062     void addNDTCell(NDTCell* cell);
00063 
00064     virtual typename SpatialIndex::CellVectorItr begin();
00065     virtual typename SpatialIndex::CellVectorItr end();
00066     virtual int size();
00067 
00069     virtual SpatialIndex* clone() const;
00071     virtual SpatialIndex* copy() const;
00072 
00074     virtual void getNeighbors(const pcl::PointXYZ &point, const double &radius, std::vector<NDTCell*> &cells);
00075 
00077     virtual void setCellType(NDTCell *type);
00078 
00079 
00080     void initKDTree();
00081 
00082     NDTCell* getClosestNDTCell(const pcl::PointXYZ &pt);
00083     std::vector<NDTCell*> getClosestNDTCells(const pcl::PointXYZ &point, double &radius);
00084     NDTCell* getCellIdx(unsigned int idx) const;
00085 
00086     void cleanCellsAboveSize(double size);
00087     int loadFromJFF(FILE * jffin);
00088 private:
00089     std::vector<NDTCell*> activeCells;
00090     NDTCell *protoType;
00091     pcl::KdTreeFLANN<pcl::PointXYZ> meansTree;
00092     typename pcl::KdTree<pcl::PointXYZ>::PointCloudPtr mp;
00093     bool treeUpdated;
00094 public:
00095     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00096 };
00097 
00098 
00099 }; //end namespace
00100 //#include <ndt_map/impl/cell_vector.hpp>
00101 
00102 #endif


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