ndt_occupancy_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 
00041 #ifndef NDT_OCCUPANCY_MAP_HH
00042 #define NDT_OCCUPANCY_MAP_HH
00043 
00044 #include <ndt_map/spatial_index.h>
00045 #include <ndt_map/ndt_cell.h>
00046 #include <ndt_map/depth_camera.h>
00047 
00048 #include <cstdlib>
00049 
00050 #include <cv.h>
00051 #include <pcl/point_cloud.h>
00052 #include <pcl/point_types.h>
00053 
00054 namespace lslgeneric
00055 {
00056 
00061 template <typename PointT>
00062 class NDTOccupancyMap
00063 {
00064 public:
00065 
00066     NDTOccupancyMap()
00067     {
00068         index_ = NULL;
00069     }
00074     NDTOccupancyMap(SpatialIndex<PointT> *idx, float _resolution)
00075     {
00076         //std::cout<<"STORE INDEX PROTOTYPE\n";
00077         index_ = idx;
00078         resolution = _resolution;
00079         //this is used to prevent memory de-allocation of the *si
00080         //si was allocated outside the NDT class and should be deallocated outside
00081         isFirstLoad_=true;
00082     }
00083 
00084     NDTOccupancyMap(const NDTOccupancyMap& other)
00085     {
00086         //std::cout<<"COPY MAP\n";
00087         if(other.index_ != NULL)
00088         {
00089             //std::cout<<"COPY INDEX\n";
00090             this->index_ = index_->copy();
00091             isFirstLoad_ = false;
00092         }
00093         this->resolution = other.resolution;
00094     }
00095 
00096     virtual ~NDTOccupancyMap()
00097     {
00098         //std::cout<<"DELETE MAP\n";
00099         if(index_ !=NULL && !isFirstLoad_)
00100         {
00101             //std::cout<<"DELETE INDEX\n";
00102             delete index_;
00103         }
00104     }
00105 
00111     void addPointCloud(const Eigen::Vector3d &origin, const pcl::PointCloud<PointT> &pc);
00112 
00113 
00114 
00116 
00120 
00121     void loadPointCloud(const pcl::PointCloud<PointT> &pc, const std::vector<std::vector<size_t> > &indices);
00122     void loadDepthImage(const cv::Mat& depthImage, DepthCamera<PointT> &cameraParams);
00123     pcl::PointCloud<PointT> loadDepthImageFeatures(const cv::Mat& depthImage, std::vector<cv::KeyPoint> &keypoints,
00124             size_t &supportSize, double maxVar, DepthCamera<PointT> &cameraParams, bool estimateParamsDI=false, bool nonMean = false);
00126 
00127     void computeNDTCells(int cellupdatemode = CELL_UPDATE_MODE_SAMPLE_VARIANCE_WITH_RESET);
00128 
00129     void writeToVRML(const char* filename);
00130     virtual void writeToVRML(FILE* fout);
00131     virtual void writeToVRML(FILE* fout, Eigen::Vector3d col);
00132 
00133     inline SpatialIndex<PointT>* getMyIndex() const
00134     {
00135         return index_;
00136     }
00138     std::string getMyIndexStr() const;
00139 
00140     //computes the likelihood of a single observation
00141     double getLikelihoodForPoint(PointT pt);
00142 
00143     //returns the covariance matrix of the closest cell to refPoint
00144     bool getCellForPoint(const PointT &refPoint, NDTCell<PointT> *&cell);
00145     std::vector<NDTCell<PointT>*> getCellsForPoint(const PointT pt, double radius);
00146 
00148     NDTCell<PointT>* getCellIdx(unsigned int idx);
00149 
00150     std::vector<NDTCell<PointT>*> pseudoTransformNDT(Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> T);
00151 
00155     std::vector<lslgeneric::NDTCell<PointT>*> getAllCells();
00156 
00160     std::vector<lslgeneric::NDTCell<PointT>*> getDynamicCells(unsigned int Timescale, float threshold);
00161 
00162 
00163     int numberOfActiveCells();
00164 
00165     //tsv: temporary debug function
00166     void debugToVRML(const char* fname, pcl::PointCloud<PointT> &pc);
00167 protected:
00168     SpatialIndex<PointT> *index_;
00169     bool isFirstLoad_;
00170     void loadPointCloud(const Eigen::Vector3d &origin, const pcl::PointCloud<PointT> &pc);
00171     float resolution;
00172 public:
00173     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00174 
00175 
00176 };
00177 
00178 } // end namespace
00179 
00180 #include <ndt_map/impl/ndt_occupancy_map.hpp>
00181 
00182 #endif


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