28 #ifndef CORELIB_SRC_OCCUPANCYGRID_H_ 29 #define CORELIB_SRC_OCCUPANCYGRID_H_ 33 #include <pcl/point_cloud.h> 34 #include <pcl/pcl_base.h> 43 inline static float logodds(
double probability)
45 return (
float)
log(probability/(1-probability));
50 return 1. - ( 1. / (1. +
exp(logodds)));
56 void setMap(
const cv::Mat & map,
float xMin,
float yMin,
float cellSize,
const std::map<int, Transform> & poses);
57 void setCellSize(
float cellSize);
59 void setCloudAssembling(
bool enabled);
65 const std::map<int, Transform> &
addedNodes()
const {
return addedNodes_;}
67 const std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > &
getCache()
const {
return cache_;}
69 template<
typename Po
intT>
70 typename pcl::PointCloud<PointT>::Ptr segmentCloud(
71 const typename pcl::PointCloud<PointT>::Ptr & cloud,
72 const pcl::IndicesPtr & indices,
74 const cv::Point3f & viewPoint,
75 pcl::IndicesPtr & groundIndices,
76 pcl::IndicesPtr & obstaclesIndices,
77 pcl::IndicesPtr * flatObstacles = 0)
const;
81 cv::Mat & groundCells,
82 cv::Mat & obstacleCells,
84 cv::Point3f & viewPoint);
89 cv::Mat & groundCells,
90 cv::Mat & obstacleCells,
92 cv::Point3f & viewPointInOut)
const;
97 const cv::Mat & ground,
98 const cv::Mat & obstacles,
99 const cv::Mat & empty);
100 bool update(
const std::map<int, Transform> & poses);
101 cv::Mat getMap(
float & xMin,
float & yMin)
const;
102 cv::Mat getProbMap(
float & xMin,
float & yMin)
const;
103 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &
getMapGround()
const {
return assembledGround_;}
104 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &
getMapObstacles()
const {
return assembledObstacles_;}
105 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &
getMapEmptyCells()
const {
return assembledEmptyCells_;}
107 unsigned long getMemoryUsed()
const;
150 std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> >
cache_;
GLM_FUNC_DECL genType log(genType const &x)
unsigned int cloudDecimation_
float getCellSize() const
std::vector< float > roiRatios_
static double probability(double logodds)
float getUpdateError() const
bool isGridFromDepth() const
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & getMapObstacles() const
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & getMapEmptyCells() const
std::map< std::string, std::string > ParametersMap
std::map< int, Transform > addedNodes_
bool isMapFrameProjection() const
static float logodds(double probability)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledGround_
float getMinMapSize() const
std::map< int, std::pair< int, int > > cellCount_
std::map< int, std::pair< std::pair< cv::Mat, cv::Mat >, cv::Mat > > cache_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledEmptyCells_
bool isFullUpdate() const
bool flatObstaclesDetected_
const std::map< int, Transform > & addedNodes() const
const std::map< int, std::pair< std::pair< cv::Mat, cv::Mat >, cv::Mat > > & getCache() const
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledObstacles_
GLM_FUNC_DECL genType exp(genType const &x)
bool normalsSegmentation_
ParametersMap parameters_
float noiseFilteringRadius_
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & getMapGround() const
bool scan2dUnknownSpaceFilled_
int noiseFilteringMinNeighbors_