OctoMap.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 SRC_OCTOMAP_H_
29 #define SRC_OCTOMAP_H_
30 
31 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
32 
33 #include <octomap/ColorOcTree.h>
34 #include <octomap/OcTreeKey.h>
35 
36 #include <pcl/pcl_base.h>
37 #include <pcl/point_types.h>
38 
39 #include <rtabmap/core/Transform.h>
41 
42 #include <map>
43 #include <unordered_set>
44 #include <string>
45 #include <queue>
46 
47 namespace rtabmap {
48 
49 // forward declaraton for "friend"
50 class RtabmapColorOcTree;
51 
53 {
54 public:
56 
57 public:
58  friend class RtabmapColorOcTree; // needs access to node children (inherited)
59 
62 
63  void setNodeRefId(int nodeRefId) {nodeRefId_ = nodeRefId;}
64  void setOccupancyType(char type) {type_=type;}
65  void setPointRef(const octomap::point3d & point) {pointRef_ = point;}
66  int getNodeRefId() const {return nodeRefId_;}
67  int getOccupancyType() const {return type_;}
68  const octomap::point3d & getPointRef() const {return pointRef_;}
69 
70  // following methods defined for octomap < 1.8 compatibility
71  RtabmapColorOcTreeNode* getChild(unsigned int i);
72  const RtabmapColorOcTreeNode* getChild(unsigned int i) const;
73  bool pruneNode();
74  void expandNode();
75  bool createChild(unsigned int i);
76 
78 
79 private:
81  int type_; // -1=undefined, 0=empty, 100=obstacle, 1=ground
83 };
84 
85 // Same as official ColorOctree but using RtabmapColorOcTreeNode, which is inheriting ColorOcTreeNode
86 class RtabmapColorOcTree : public octomap::OccupancyOcTreeBase <RtabmapColorOcTreeNode> {
87 
88  public:
90  RtabmapColorOcTree(double resolution);
91  virtual ~RtabmapColorOcTree() {}
92 
95  RtabmapColorOcTree* create() const {return new RtabmapColorOcTree(resolution); }
96 
97  std::string getTreeType() const {return "ColorOcTree";} // same type as ColorOcTree to be compatible with ROS OctoMap msg
98 
105  virtual bool pruneNode(RtabmapColorOcTreeNode* node);
106 
107  virtual bool isNodeCollapsible(const RtabmapColorOcTreeNode* node) const;
108 
109  // set node color at given key or coordinate. Replaces previous color.
110  RtabmapColorOcTreeNode* setNodeColor(const octomap::OcTreeKey& key, uint8_t r,
111  uint8_t g, uint8_t b);
112 
114  float z, uint8_t r,
115  uint8_t g, uint8_t b) {
116  octomap::OcTreeKey key;
117  if (!this->coordToKeyChecked(octomap::point3d(x,y,z), key)) return NULL;
118  return setNodeColor(key,r,g,b);
119  }
120 
121  // integrate color measurement at given key or coordinate. Average with previous color
122  RtabmapColorOcTreeNode* averageNodeColor(const octomap::OcTreeKey& key, uint8_t r,
123  uint8_t g, uint8_t b);
124 
126  float z, uint8_t r,
127  uint8_t g, uint8_t b) {
129  if (!this->coordToKeyChecked(octomap::point3d(x,y,z), key)) return NULL;
130  return averageNodeColor(key,r,g,b);
131  }
132 
133  // integrate color measurement at given key or coordinate. Average with previous color
134  RtabmapColorOcTreeNode* integrateNodeColor(const octomap::OcTreeKey& key, uint8_t r,
135  uint8_t g, uint8_t b);
136 
138  float z, uint8_t r,
139  uint8_t g, uint8_t b) {
140  octomap::OcTreeKey key;
141  if (!this->coordToKeyChecked(octomap::point3d(x,y,z), key)) return NULL;
142  return integrateNodeColor(key,r,g,b);
143  }
144 
145  // update inner nodes, sets color to average child color
146  void updateInnerOccupancy();
147 
148  protected:
149  void updateInnerOccupancyRecurs(RtabmapColorOcTreeNode* node, unsigned int depth);
150 
159  public:
161 
167  void ensureLinking() {};
168  };
171 
172  };
173 
175 public:
176  OctoMap(const ParametersMap & parameters = ParametersMap());
177 
178  const std::map<int, Transform> & addedNodes() const {return addedNodes_;}
179  void addToCache(int nodeId,
180  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & ground,
181  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & obstacles,
182  const pcl::PointXYZ & viewPoint);
183  void addToCache(int nodeId,
184  const cv::Mat & ground,
185  const cv::Mat & obstacles,
186  const cv::Mat & empty,
187  const cv::Point3f & viewPoint);
188  bool update(const std::map<int, Transform> & poses); // return true if map has changed
189 
190  const RtabmapColorOcTree * octree() const {return octree_;}
191 
192  pcl::PointCloud<pcl::PointXYZRGB>::Ptr createCloud(
193  unsigned int treeDepth = 0,
194  std::vector<int> * obstacleIndices = 0,
195  std::vector<int> * emptyIndices = 0,
196  std::vector<int> * groundIndices = 0,
197  bool originalRefPoints = true,
198  std::vector<int> * frontierIndices = 0,
199  std::vector<double> * cloudProb = 0) const;
200 
201  cv::Mat createProjectionMap(
202  float & xMin,
203  float & yMin,
204  float & gridCellSize,
205  float minGridSize = 0.0f,
206  unsigned int treeDepth = 0);
207 
208  bool writeBinary(const std::string & path);
209 
210  virtual ~OctoMap();
211  void clear();
212 
213  void getGridMin(double & x, double & y, double & z) const {x=minValues_[0];y=minValues_[1];z=minValues_[2];}
214  void getGridMax(double & x, double & y, double & z) const {x=maxValues_[0];y=maxValues_[1];z=maxValues_[2];}
215 
216  void setMaxRange(float value) {rangeMax_ = value;}
217  void setRayTracing(bool enabled) {rayTracing_ = enabled;}
218  bool hasColor() const {return hasColor_;}
219 
220  static std::unordered_set<octomap::OcTreeKey, octomap::OcTreeKey::KeyHash> findEmptyNode(RtabmapColorOcTree* octree_, unsigned int treeDepth, octomap::point3d startPosition);
221  static void floodFill(RtabmapColorOcTree* octree_, unsigned int treeDepth,octomap::point3d startPosition, std::unordered_set<octomap::OcTreeKey, octomap::OcTreeKey::KeyHash> & EmptyNodes,std::queue<octomap::point3d>& positionToExplore);
222  static bool isNodeVisited(std::unordered_set<octomap::OcTreeKey,octomap::OcTreeKey::KeyHash> const & EmptyNodes,octomap::OcTreeKey const key);
223  static octomap::point3d findCloseEmpty(RtabmapColorOcTree* octree_, unsigned int treeDepth,octomap::point3d startPosition);
224  static bool isValidEmpty(RtabmapColorOcTree* octree_, unsigned int treeDepth,octomap::point3d startPosition);
225 
226 private:
227  void updateMinMax(const octomap::point3d & point);
228 
229 private:
230  std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > cache_; // [id: < <ground, obstacles>, empty>]
231  std::map<int, std::pair<const pcl::PointCloud<pcl::PointXYZRGB>::Ptr, const pcl::PointCloud<pcl::PointXYZRGB>::Ptr> > cacheClouds_; // [id: <ground, obstacles>]
232  std::map<int, cv::Point3f> cacheViewPoints_;
234  std::map<int, Transform> addedNodes_;
235  bool hasColor_;
238  float rangeMax_;
240  unsigned int emptyFloodFillDepth_;
241  double minValues_[3];
242  double maxValues_[3];
243 };
244 
245 } /* namespace rtabmap */
246 
247 #endif /* SRC_OCTOMAP_H_ */
#define NULL
bool hasColor() const
Definition: OctoMap.h:218
RtabmapColorOcTreeNode * integrateNodeColor(float x, float y, float z, uint8_t r, uint8_t g, uint8_t b)
Definition: OctoMap.h:137
f
virtual ~RtabmapColorOcTree()
Definition: OctoMap.h:91
octomap::point3d pointRef_
Definition: OctoMap.h:82
static StaticMemberInitializer RtabmapColorOcTreeMemberInit
static member to ensure static initialization (only once)
Definition: OctoMap.h:170
void getGridMin(double &x, double &y, double &z) const
Definition: OctoMap.h:213
std::map< int, Transform > addedNodes_
Definition: OctoMap.h:234
bool createChild(unsigned int i)
Definition: OctoMap.cpp:98
bool fullUpdate_
Definition: OctoMap.h:236
std::map< int, cv::Point3f > cacheViewPoints_
Definition: OctoMap.h:232
RtabmapColorOcTreeNode * getChild(unsigned int i)
Definition: OctoMap.cpp:45
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
RtabmapColorOcTreeNode(const RtabmapColorOcTreeNode &rhs)
Definition: OctoMap.h:61
void setPointRef(const octomap::point3d &point)
Definition: OctoMap.h:65
RtabmapColorOcTree * create() const
Definition: OctoMap.h:95
void getGridMax(double &x, double &y, double &z) const
Definition: OctoMap.h:214
void setNodeRefId(int nodeRefId)
Definition: OctoMap.h:63
RtabmapColorOcTreeNode * setNodeColor(float x, float y, float z, uint8_t r, uint8_t g, uint8_t b)
Definition: OctoMap.h:113
detail::uint8 uint8_t
Definition: fwd.hpp:908
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
std::map< int, std::pair< std::pair< cv::Mat, cv::Mat >, cv::Mat > > cache_
Definition: OctoMap.h:230
const std::map< int, Transform > & addedNodes() const
Definition: OctoMap.h:178
std::map< int, std::pair< const pcl::PointCloud< pcl::PointXYZRGB >::Ptr, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr > > cacheClouds_
Definition: OctoMap.h:231
friend class RtabmapColorOcTree
Definition: OctoMap.h:58
RtabmapColorOcTree * octree_
Definition: OctoMap.h:233
const RtabmapColorOcTree * octree() const
Definition: OctoMap.h:190
unsigned int emptyFloodFillDepth_
Definition: OctoMap.h:240
const octomap::point3d & getPointRef() const
Definition: OctoMap.h:68
void setOccupancyType(char type)
Definition: OctoMap.h:64
void setMaxRange(float value)
Definition: OctoMap.h:216
float rangeMax_
Definition: OctoMap.h:238
std::string getTreeType() const
Definition: OctoMap.h:97
bool rayTracing_
Definition: OctoMap.h:239
RtabmapColorOcTreeNode * averageNodeColor(float x, float y, float z, uint8_t r, uint8_t g, uint8_t b)
Definition: OctoMap.h:125
void setRayTracing(bool enabled)
Definition: OctoMap.h:217
float updateError_
Definition: OctoMap.h:237


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