28 #ifndef SRC_OCTOMAP_H_ 29 #define SRC_OCTOMAP_H_ 36 #include <pcl/pcl_base.h> 37 #include <pcl/point_types.h> 43 #include <unordered_set> 50 class RtabmapColorOcTree;
118 return setNodeColor(key,r,g,b);
130 return averageNodeColor(key,r,g,b);
142 return integrateNodeColor(key,r,g,b);
146 void updateInnerOccupancy();
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);
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;
201 cv::Mat createProjectionMap(
204 float & gridCellSize,
205 float minGridSize = 0.0
f,
206 unsigned int treeDepth = 0);
208 bool writeBinary(
const std::string & path);
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];}
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);
230 std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> >
cache_;
231 std::map<int, std::pair<const pcl::PointCloud<pcl::PointXYZRGB>::Ptr,
const pcl::PointCloud<pcl::PointXYZRGB>::Ptr> >
cacheClouds_;
241 double minValues_[3];
242 double maxValues_[3];
int getOccupancyType() const
RtabmapColorOcTreeNode * integrateNodeColor(float x, float y, float z, uint8_t r, uint8_t g, uint8_t b)
virtual ~RtabmapColorOcTree()
octomap::point3d pointRef_
static StaticMemberInitializer RtabmapColorOcTreeMemberInit
static member to ensure static initialization (only once)
void getGridMin(double &x, double &y, double &z) const
std::map< int, Transform > addedNodes_
bool createChild(unsigned int i)
std::map< int, cv::Point3f > cacheViewPoints_
RtabmapColorOcTreeNode * getChild(unsigned int i)
std::map< std::string, std::string > ParametersMap
RtabmapColorOcTreeNode(const RtabmapColorOcTreeNode &rhs)
void setPointRef(const octomap::point3d &point)
RtabmapColorOcTree * create() const
void getGridMax(double &x, double &y, double &z) const
void setNodeRefId(int nodeRefId)
RtabmapColorOcTreeNode * setNodeColor(float x, float y, float z, uint8_t r, uint8_t g, uint8_t b)
std::map< int, std::pair< std::pair< cv::Mat, cv::Mat >, cv::Mat > > cache_
const std::map< int, Transform > & addedNodes() const
std::map< int, std::pair< const pcl::PointCloud< pcl::PointXYZRGB >::Ptr, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr > > cacheClouds_
friend class RtabmapColorOcTree
RtabmapColorOcTree * octree_
const RtabmapColorOcTree * octree() const
unsigned int emptyFloodFillDepth_
const octomap::point3d & getPointRef() const
void setOccupancyType(char type)
void setMaxRange(float value)
std::string getTreeType() const
RtabmapColorOcTreeNode * averageNodeColor(float x, float y, float z, uint8_t r, uint8_t g, uint8_t b)
void updateOccupancyTypeChildren()
void setRayTracing(bool enabled)