Go to the documentation of this file.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
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
00077 index_ = idx;
00078 resolution = _resolution;
00079
00080
00081 isFirstLoad_=true;
00082 }
00083
00084 NDTOccupancyMap(const NDTOccupancyMap& other)
00085 {
00086
00087 if(other.index_ != NULL)
00088 {
00089
00090 this->index_ = index_->copy();
00091 isFirstLoad_ = false;
00092 }
00093 this->resolution = other.resolution;
00094 }
00095
00096 virtual ~NDTOccupancyMap()
00097 {
00098
00099 if(index_ !=NULL && !isFirstLoad_)
00100 {
00101
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 virtual void writeToVRML(FILE* fout);
00130 virtual void writeToVRML(FILE* fout, Eigen::Vector3d col);
00131
00132 inline SpatialIndex<PointT>* getMyIndex() const
00133 {
00134 return index_;
00135 }
00137 std::string getMyIndexStr() const;
00138
00139
00140 double getLikelihoodForPoint(PointT pt);
00141
00142
00143 bool getCellForPoint(const PointT &refPoint, NDTCell<PointT> *&cell);
00144 std::vector<NDTCell<PointT>*> getCellsForPoint(const PointT pt, double radius);
00145
00147 NDTCell<PointT>* getCellIdx(unsigned int idx);
00148
00149 std::vector<NDTCell<PointT>*> pseudoTransformNDT(Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> T);
00150
00154 std::vector<lslgeneric::NDTCell<PointT>*> getAllCells();
00155
00159 std::vector<lslgeneric::NDTCell<PointT>*> getDynamicCells(unsigned int Timescale, float threshold);
00160
00161
00162 int numberOfActiveCells();
00163
00164
00165 void debugToVRML(const char* fname, pcl::PointCloud<PointT> &pc);
00166 protected:
00167 SpatialIndex<PointT> *index_;
00168 bool isFirstLoad_;
00169 void loadPointCloud(const Eigen::Vector3d &origin, const pcl::PointCloud<PointT> &pc);
00170 float resolution;
00171 public:
00172 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00173
00174
00175 };
00176
00177 }
00178
00179 #include <ndt_map/impl/ndt_occupancy_map.hpp>
00180
00181 #endif