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 #ifndef CORELIB_SRC_OCCUPANCYGRID_H_
00029 #define CORELIB_SRC_OCCUPANCYGRID_H_
00030
00031 #include "rtabmap/core/RtabmapExp.h"
00032
00033 #include <pcl/point_cloud.h>
00034 #include <pcl/pcl_base.h>
00035 #include <rtabmap/core/Parameters.h>
00036 #include <rtabmap/core/Signature.h>
00037
00038 namespace rtabmap {
00039
00040 class RTABMAP_EXP OccupancyGrid
00041 {
00042 public:
00043 inline static float logodds(double probability)
00044 {
00045 return (float) log(probability/(1-probability));
00046 }
00047
00048 inline static double probability(double logodds)
00049 {
00050 return 1. - ( 1. / (1. + exp(logodds)));
00051 }
00052
00053 public:
00054 OccupancyGrid(const ParametersMap & parameters = ParametersMap());
00055 void parseParameters(const ParametersMap & parameters);
00056 void setMap(const cv::Mat & map, float xMin, float yMin, float cellSize, const std::map<int, Transform> & poses);
00057 void setCellSize(float cellSize);
00058 float getCellSize() const {return cellSize_;}
00059 void setCloudAssembling(bool enabled);
00060 float getMinMapSize() const {return minMapSize_;}
00061 bool isGridFromDepth() const {return occupancyFromDepth_;}
00062 bool isFullUpdate() const {return fullUpdate_;}
00063 float getUpdateError() const {return updateError_;}
00064 bool isMapFrameProjection() const {return projMapFrame_;}
00065 const std::map<int, Transform> & addedNodes() const {return addedNodes_;}
00066 int cacheSize() const {return (int)cache_.size();}
00067 const std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > & getCache() const {return cache_;}
00068
00069 template<typename PointT>
00070 typename pcl::PointCloud<PointT>::Ptr segmentCloud(
00071 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00072 const pcl::IndicesPtr & indices,
00073 const Transform & pose,
00074 const cv::Point3f & viewPoint,
00075 pcl::IndicesPtr & groundIndices,
00076 pcl::IndicesPtr & obstaclesIndices,
00077 pcl::IndicesPtr * flatObstacles = 0) const;
00078
00079 void createLocalMap(
00080 const Signature & node,
00081 cv::Mat & groundCells,
00082 cv::Mat & obstacleCells,
00083 cv::Mat & emptyCells,
00084 cv::Point3f & viewPoint) const;
00085
00086 void createLocalMap(
00087 const LaserScan & cloud,
00088 const Transform & pose,
00089 cv::Mat & groundCells,
00090 cv::Mat & obstacleCells,
00091 cv::Mat & emptyCells,
00092 cv::Point3f & viewPointInOut) const;
00093
00094 void clear();
00095 void addToCache(
00096 int nodeId,
00097 const cv::Mat & ground,
00098 const cv::Mat & obstacles,
00099 const cv::Mat & empty);
00100 void update(const std::map<int, Transform> & poses);
00101 cv::Mat getMap(float & xMin, float & yMin) const;
00102 cv::Mat getProbMap(float & xMin, float & yMin) const;
00103 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & getMapGround() const {return assembledGround_;}
00104 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & getMapObstacles() const {return assembledObstacles_;}
00105 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & getMapEmptyCells() const {return assembledEmptyCells_;}
00106
00107 private:
00108 ParametersMap parameters_;
00109 int cloudDecimation_;
00110 float cloudMaxDepth_;
00111 float cloudMinDepth_;
00112 std::vector<float> roiRatios_;
00113 float footprintLength_;
00114 float footprintWidth_;
00115 float footprintHeight_;
00116 int scanDecimation_;
00117 float cellSize_;
00118 bool preVoxelFiltering_;
00119 bool occupancyFromDepth_;
00120 bool projMapFrame_;
00121 float maxObstacleHeight_;
00122 int normalKSearch_;
00123 float maxGroundAngle_;
00124 float clusterRadius_;
00125 int minClusterSize_;
00126 bool flatObstaclesDetected_;
00127 float minGroundHeight_;
00128 float maxGroundHeight_;
00129 bool normalsSegmentation_;
00130 bool grid3D_;
00131 bool groundIsObstacle_;
00132 float noiseFilteringRadius_;
00133 int noiseFilteringMinNeighbors_;
00134 bool scan2dUnknownSpaceFilled_;
00135 bool rayTracing_;
00136 bool fullUpdate_;
00137 float minMapSize_;
00138 bool erode_;
00139 float footprintRadius_;
00140 float updateError_;
00141 float occupancyThr_;
00142 float probHit_;
00143 float probMiss_;
00144 float probClampingMin_;
00145 float probClampingMax_;
00146
00147 std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > cache_;
00148 cv::Mat map_;
00149 cv::Mat mapInfo_;
00150 std::map<int, std::pair<int, int> > cellCount_;
00151 float xMin_;
00152 float yMin_;
00153 std::map<int, Transform> addedNodes_;
00154
00155 bool cloudAssembling_;
00156 pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledGround_;
00157 pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledObstacles_;
00158 pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledEmptyCells_;
00159 };
00160
00161 }
00162
00163 #include <rtabmap/core/impl/OccupancyGrid.hpp>
00164
00165 #endif