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 SRC_OCTOMAP_H_
00029 #define SRC_OCTOMAP_H_
00030
00031 #include "rtabmap/core/RtabmapExp.h"
00032
00033 #include <octomap/ColorOcTree.h>
00034 #include <octomap/OcTreeKey.h>
00035
00036 #include <pcl/pcl_base.h>
00037 #include <pcl/point_types.h>
00038
00039 #include <rtabmap/core/Transform.h>
00040 #include <rtabmap/core/Parameters.h>
00041
00042 #include <map>
00043 #include <string>
00044
00045 namespace rtabmap {
00046
00047
00048 class RtabmapColorOcTree;
00049
00050 class RtabmapColorOcTreeNode : public octomap::ColorOcTreeNode
00051 {
00052 public:
00053 enum OccupancyType {kTypeUnknown=-1, kTypeEmpty=0, kTypeGround=1, kTypeObstacle=100};
00054
00055 public:
00056 friend class RtabmapColorOcTree;
00057
00058 RtabmapColorOcTreeNode() : ColorOcTreeNode(), nodeRefId_(0), type_(kTypeUnknown) {}
00059 RtabmapColorOcTreeNode(const RtabmapColorOcTreeNode& rhs) : ColorOcTreeNode(rhs), nodeRefId_(rhs.nodeRefId_), type_(rhs.type_) {}
00060
00061 void setNodeRefId(int nodeRefId) {nodeRefId_ = nodeRefId;}
00062 void setOccupancyType(char type) {type_=type;}
00063 void setPointRef(const octomap::point3d & point) {pointRef_ = point;}
00064 int getNodeRefId() const {return nodeRefId_;}
00065 int getOccupancyType() const {return type_;}
00066 const octomap::point3d & getPointRef() const {return pointRef_;}
00067
00068
00069 RtabmapColorOcTreeNode* getChild(unsigned int i);
00070 const RtabmapColorOcTreeNode* getChild(unsigned int i) const;
00071 bool pruneNode();
00072 void expandNode();
00073 bool createChild(unsigned int i);
00074
00075 private:
00076 int nodeRefId_;
00077 int type_;
00078 octomap::point3d pointRef_;
00079 };
00080
00081
00082 class RtabmapColorOcTree : public octomap::OccupancyOcTreeBase <RtabmapColorOcTreeNode> {
00083
00084 public:
00086 RtabmapColorOcTree(double resolution);
00087
00090 RtabmapColorOcTree* create() const {return new RtabmapColorOcTree(resolution); }
00091
00092 std::string getTreeType() const {return "ColorOcTree";}
00093
00100 virtual bool pruneNode(RtabmapColorOcTreeNode* node);
00101
00102 virtual bool isNodeCollapsible(const RtabmapColorOcTreeNode* node) const;
00103
00104
00105 RtabmapColorOcTreeNode* setNodeColor(const octomap::OcTreeKey& key, uint8_t r,
00106 uint8_t g, uint8_t b);
00107
00108 RtabmapColorOcTreeNode* setNodeColor(float x, float y,
00109 float z, uint8_t r,
00110 uint8_t g, uint8_t b) {
00111 octomap::OcTreeKey key;
00112 if (!this->coordToKeyChecked(octomap::point3d(x,y,z), key)) return NULL;
00113 return setNodeColor(key,r,g,b);
00114 }
00115
00116
00117 RtabmapColorOcTreeNode* averageNodeColor(const octomap::OcTreeKey& key, uint8_t r,
00118 uint8_t g, uint8_t b);
00119
00120 RtabmapColorOcTreeNode* averageNodeColor(float x, float y,
00121 float z, uint8_t r,
00122 uint8_t g, uint8_t b) {
00123 octomap:: OcTreeKey key;
00124 if (!this->coordToKeyChecked(octomap::point3d(x,y,z), key)) return NULL;
00125 return averageNodeColor(key,r,g,b);
00126 }
00127
00128
00129 RtabmapColorOcTreeNode* integrateNodeColor(const octomap::OcTreeKey& key, uint8_t r,
00130 uint8_t g, uint8_t b);
00131
00132 RtabmapColorOcTreeNode* integrateNodeColor(float x, float y,
00133 float z, uint8_t r,
00134 uint8_t g, uint8_t b) {
00135 octomap::OcTreeKey key;
00136 if (!this->coordToKeyChecked(octomap::point3d(x,y,z), key)) return NULL;
00137 return integrateNodeColor(key,r,g,b);
00138 }
00139
00140
00141 void updateInnerOccupancy();
00142
00143 protected:
00144 void updateInnerOccupancyRecurs(RtabmapColorOcTreeNode* node, unsigned int depth);
00145
00153 class StaticMemberInitializer{
00154 public:
00155 StaticMemberInitializer();
00156
00162 void ensureLinking() {};
00163 };
00165 static StaticMemberInitializer RtabmapColorOcTreeMemberInit;
00166
00167 };
00168
00169 class RTABMAP_EXP OctoMap {
00170 public:
00171 static void HSVtoRGB(float *r, float *g, float *b, float h, float s, float v);
00172
00173 public:
00174 OctoMap(const ParametersMap & parameters);
00175 OctoMap(float cellSize = 0.1f, float occupancyThr = 0.5f, bool fullUpdate = false, float updateError=0.01f);
00176
00177 const std::map<int, Transform> & addedNodes() const {return addedNodes_;}
00178 void addToCache(int nodeId,
00179 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & ground,
00180 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & obstacles,
00181 const pcl::PointXYZ & viewPoint);
00182 void addToCache(int nodeId,
00183 const cv::Mat & ground,
00184 const cv::Mat & obstacles,
00185 const cv::Mat & empty,
00186 const cv::Point3f & viewPoint);
00187 void update(const std::map<int, Transform> & poses);
00188
00189 const RtabmapColorOcTree * octree() const {return octree_;}
00190
00191 pcl::PointCloud<pcl::PointXYZRGB>::Ptr createCloud(
00192 unsigned int treeDepth = 0,
00193 std::vector<int> * obstacleIndices = 0,
00194 std::vector<int> * emptyIndices = 0,
00195 std::vector<int> * groundIndices = 0,
00196 bool originalRefPoints = true) const;
00197
00198 cv::Mat createProjectionMap(
00199 float & xMin,
00200 float & yMin,
00201 float & gridCellSize,
00202 float minGridSize = 0.0f,
00203 unsigned int treeDepth = 0);
00204
00205 bool writeBinary(const std::string & path);
00206
00207 virtual ~OctoMap();
00208 void clear();
00209
00210 void getGridMin(double & x, double & y, double & z) const {x=minValues_[0];y=minValues_[1];z=minValues_[2];}
00211 void getGridMax(double & x, double & y, double & z) const {x=maxValues_[0];y=maxValues_[1];z=maxValues_[2];}
00212
00213 void setMaxRange(float value) {rangeMax_ = value;}
00214 void setRayTracing(bool enabled) {rayTracing_ = enabled;}
00215 bool hasColor() const {return hasColor_;}
00216
00217 private:
00218 void updateMinMax(const octomap::point3d & point);
00219
00220 private:
00221 std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > cache_;
00222 std::map<int, std::pair<const pcl::PointCloud<pcl::PointXYZRGB>::Ptr, const pcl::PointCloud<pcl::PointXYZRGB>::Ptr> > cacheClouds_;
00223 std::map<int, cv::Point3f> cacheViewPoints_;
00224 RtabmapColorOcTree * octree_;
00225 std::map<int, Transform> addedNodes_;
00226 octomap::KeyRay keyRay_;
00227 bool hasColor_;
00228 bool fullUpdate_;
00229 float updateError_;
00230 float rangeMax_;
00231 bool rayTracing_;
00232 double minValues_[3];
00233 double maxValues_[3];
00234 };
00235
00236 }
00237
00238 #endif