Go to the documentation of this file.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
00041 #include <map>
00042 #include <string>
00043
00044 namespace rtabmap {
00045
00046 class OcTreeNodeInfo
00047 {
00048 public:
00049 OcTreeNodeInfo(int nodeRefId, const octomap::OcTreeKey & key, bool isObstacle) :
00050 nodeRefId_(nodeRefId),
00051 key_(key),
00052 isObstacle_(isObstacle) {}
00053 int nodeRefId_;
00054 octomap::OcTreeKey key_;
00055 bool isObstacle_;
00056 };
00057
00058 class RTABMAP_EXP OctoMap {
00059 public:
00060 OctoMap(float voxelSize = 0.1f);
00061
00062 const std::map<int, Transform> & addedNodes() const {return addedNodes_;}
00063 void addToCache(int nodeId,
00064 pcl::PointCloud<pcl::PointXYZRGB>::Ptr & ground,
00065 pcl::PointCloud<pcl::PointXYZRGB>::Ptr & obstacles);
00066 void update(const std::map<int, Transform> & poses);
00067
00068 const octomap::ColorOcTree * octree() const {return octree_;}
00069
00070 pcl::PointCloud<pcl::PointXYZRGB>::Ptr createCloud(
00071 unsigned int treeDepth = 0,
00072 std::vector<int> * obstacleIndices = 0,
00073 std::vector<int> * emptyIndices = 0) const;
00074
00075 cv::Mat createProjectionMap(
00076 float & xMin,
00077 float & yMin,
00078 float & gridCellSize,
00079 float minGridSize);
00080
00081 bool writeBinary(const std::string & path);
00082
00083 virtual ~OctoMap();
00084 void clear();
00085
00086 private:
00087 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> > cache_;
00088 octomap::ColorOcTree * octree_;
00089 std::map<octomap::ColorOcTreeNode*, OcTreeNodeInfo> occupiedCells_;
00090 std::map<int, Transform> addedNodes_;
00091 octomap::KeyRay keyRay_;
00092 };
00093
00094 }
00095
00096 #endif