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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:32