OccupancyGrid.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef CORELIB_SRC_OCCUPANCYGRID_H_
29 #define CORELIB_SRC_OCCUPANCYGRID_H_
30 
31 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
32 
33 #include <pcl/point_cloud.h>
34 #include <pcl/pcl_base.h>
36 #include <rtabmap/core/Signature.h>
37 
38 namespace rtabmap {
39 
41 {
42 public:
43  inline static float logodds(double probability)
44  {
45  return (float) log(probability/(1-probability));
46  }
47 
48  inline static double probability(double logodds)
49  {
50  return 1. - ( 1. / (1. + exp(logodds)));
51  }
52 
53 public:
54  OccupancyGrid(const ParametersMap & parameters = ParametersMap());
55  void parseParameters(const ParametersMap & parameters);
56  void setMap(const cv::Mat & map, float xMin, float yMin, float cellSize, const std::map<int, Transform> & poses);
57  void setCellSize(float cellSize);
58  float getCellSize() const {return cellSize_;}
59  void setCloudAssembling(bool enabled);
60  float getMinMapSize() const {return minMapSize_;}
61  bool isGridFromDepth() const {return occupancySensor_;}
62  bool isFullUpdate() const {return fullUpdate_;}
63  float getUpdateError() const {return updateError_;}
64  bool isMapFrameProjection() const {return projMapFrame_;}
65  const std::map<int, Transform> & addedNodes() const {return addedNodes_;}
66  int cacheSize() const {return (int)cache_.size();}
67  const std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > & getCache() const {return cache_;}
68 
69  template<typename PointT>
70  typename pcl::PointCloud<PointT>::Ptr segmentCloud(
71  const typename pcl::PointCloud<PointT>::Ptr & cloud,
72  const pcl::IndicesPtr & indices,
73  const Transform & pose,
74  const cv::Point3f & viewPoint,
75  pcl::IndicesPtr & groundIndices, // output cloud indices
76  pcl::IndicesPtr & obstaclesIndices, // output cloud indices
77  pcl::IndicesPtr * flatObstacles = 0) const; // output cloud indices
78 
79  void createLocalMap(
80  const Signature & node,
81  cv::Mat & groundCells,
82  cv::Mat & obstacleCells,
83  cv::Mat & emptyCells,
84  cv::Point3f & viewPoint);
85 
86  void createLocalMap(
87  const LaserScan & cloud,
88  const Transform & pose,
89  cv::Mat & groundCells,
90  cv::Mat & obstacleCells,
91  cv::Mat & emptyCells,
92  cv::Point3f & viewPointInOut) const;
93 
94  void clear();
95  void addToCache(
96  int nodeId,
97  const cv::Mat & ground,
98  const cv::Mat & obstacles,
99  const cv::Mat & empty);
100  bool update(const std::map<int, Transform> & poses); // return true if map has changed
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_;}
106 
107  unsigned long getMemoryUsed() const;
108 
109 private:
111  unsigned int cloudDecimation_;
114  std::vector<float> roiRatios_;
119  float cellSize_;
133  bool grid3D_;
140  float minMapSize_;
141  bool erode_;
145  float probHit_;
146  float probMiss_;
149 
150  std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > cache_; //<node id, < <ground, obstacles>, empty> >
151  cv::Mat map_;
152  cv::Mat mapInfo_;
153  std::map<int, std::pair<int, int> > cellCount_; //<node Id, cells>
154  float xMin_;
155  float yMin_;
156  std::map<int, Transform> addedNodes_;
157 
159  pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledGround_;
160  pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledObstacles_;
161  pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledEmptyCells_;
162 };
163 
164 }
165 
167 
168 #endif /* CORELIB_SRC_OCCUPANCYGRID_H_ */
GLM_FUNC_DECL genType log(genType const &x)
unsigned int cloudDecimation_
float getCellSize() const
Definition: OccupancyGrid.h:58
std::vector< float > roiRatios_
static double probability(double logodds)
Definition: OccupancyGrid.h:48
float getUpdateError() const
Definition: OccupancyGrid.h:63
bool isGridFromDepth() const
Definition: OccupancyGrid.h:61
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & getMapObstacles() const
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & getMapEmptyCells() const
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
std::map< int, Transform > addedNodes_
bool isMapFrameProjection() const
Definition: OccupancyGrid.h:64
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
static float logodds(double probability)
Definition: OccupancyGrid.h:43
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledGround_
float getMinMapSize() const
Definition: OccupancyGrid.h:60
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
Definition: OccupancyGrid.h:62
const std::map< int, Transform > & addedNodes() const
Definition: OccupancyGrid.h:65
const std::map< int, std::pair< std::pair< cv::Mat, cv::Mat >, cv::Mat > > & getCache() const
Definition: OccupancyGrid.h:67
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledObstacles_
GLM_FUNC_DECL genType exp(genType const &x)
ParametersMap parameters_
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & getMapGround() const


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:29