Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | List of all members
rtabmap::OctoMap Class Reference

#include <OctoMap.h>

Public Member Functions

const std::map< int, Transform > & addedNodes () const
 
void addToCache (int nodeId, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &ground, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &obstacles, const pcl::PointXYZ &viewPoint)
 
void addToCache (int nodeId, const cv::Mat &ground, const cv::Mat &obstacles, const cv::Mat &empty, const cv::Point3f &viewPoint)
 
void clear ()
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr createCloud (unsigned int treeDepth=0, std::vector< int > *obstacleIndices=0, std::vector< int > *emptyIndices=0, std::vector< int > *groundIndices=0, bool originalRefPoints=true, std::vector< int > *frontierIndices=0, std::vector< double > *cloudProb=0) const
 
cv::Mat createProjectionMap (float &xMin, float &yMin, float &gridCellSize, float minGridSize=0.0f, unsigned int treeDepth=0)
 
void getGridMax (double &x, double &y, double &z) const
 
void getGridMin (double &x, double &y, double &z) const
 
bool hasColor () const
 
 OctoMap (const ParametersMap &parameters=ParametersMap())
 
const RtabmapColorOcTreeoctree () const
 
void setMaxRange (float value)
 
void setRayTracing (bool enabled)
 
bool update (const std::map< int, Transform > &poses)
 
bool writeBinary (const std::string &path)
 
virtual ~OctoMap ()
 

Static Public Member Functions

static octomap::point3d findCloseEmpty (RtabmapColorOcTree *octree_, unsigned int treeDepth, octomap::point3d startPosition)
 
static std::unordered_set< octomap::OcTreeKey, octomap::OcTreeKey::KeyHashfindEmptyNode (RtabmapColorOcTree *octree_, unsigned int treeDepth, octomap::point3d startPosition)
 
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)
 
static bool isNodeVisited (std::unordered_set< octomap::OcTreeKey, octomap::OcTreeKey::KeyHash > const &EmptyNodes, octomap::OcTreeKey const key)
 
static bool isValidEmpty (RtabmapColorOcTree *octree_, unsigned int treeDepth, octomap::point3d startPosition)
 

Private Member Functions

void updateMinMax (const octomap::point3d &point)
 

Private Attributes

std::map< int, TransformaddedNodes_
 
std::map< int, std::pair< std::pair< cv::Mat, cv::Mat >, cv::Mat > > cache_
 
std::map< int, std::pair< const pcl::PointCloud< pcl::PointXYZRGB >::Ptr, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr > > cacheClouds_
 
std::map< int, cv::Point3f > cacheViewPoints_
 
unsigned int emptyFloodFillDepth_
 
bool fullUpdate_
 
bool hasColor_
 
double maxValues_ [3]
 
double minValues_ [3]
 
RtabmapColorOcTreeoctree_
 
float rangeMax_
 
bool rayTracing_
 
float updateError_
 

Detailed Description

Definition at line 174 of file OctoMap.h.

Constructor & Destructor Documentation

◆ OctoMap()

rtabmap::OctoMap::OctoMap ( const ParametersMap parameters = ParametersMap())

Definition at line 291 of file OctoMap.cpp.

◆ ~OctoMap()

rtabmap::OctoMap::~OctoMap ( )
virtual

Definition at line 345 of file OctoMap.cpp.

Member Function Documentation

◆ addedNodes()

const std::map<int, Transform>& rtabmap::OctoMap::addedNodes ( ) const
inline

Definition at line 178 of file OctoMap.h.

◆ addToCache() [1/2]

void rtabmap::OctoMap::addToCache ( int  nodeId,
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  ground,
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  obstacles,
const pcl::PointXYZ &  viewPoint 
)

Definition at line 363 of file OctoMap.cpp.

◆ addToCache() [2/2]

void rtabmap::OctoMap::addToCache ( int  nodeId,
const cv::Mat &  ground,
const cv::Mat &  obstacles,
const cv::Mat &  empty,
const cv::Point3f &  viewPoint 
)

Definition at line 378 of file OctoMap.cpp.

◆ clear()

void rtabmap::OctoMap::clear ( )

Definition at line 351 of file OctoMap.cpp.

◆ createCloud()

pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::OctoMap::createCloud ( unsigned int  treeDepth = 0,
std::vector< int > *  obstacleIndices = 0,
std::vector< int > *  emptyIndices = 0,
std::vector< int > *  groundIndices = 0,
bool  originalRefPoints = true,
std::vector< int > *  frontierIndices = 0,
std::vector< double > *  cloudProb = 0 
) const

Definition at line 1054 of file OctoMap.cpp.

◆ createProjectionMap()

cv::Mat rtabmap::OctoMap::createProjectionMap ( float &  xMin,
float &  yMin,
float &  gridCellSize,
float  minGridSize = 0.0f,
unsigned int  treeDepth = 0 
)

Definition at line 1218 of file OctoMap.cpp.

◆ findCloseEmpty()

octomap::point3d rtabmap::OctoMap::findCloseEmpty ( RtabmapColorOcTree octree_,
unsigned int  treeDepth,
octomap::point3d  startPosition 
)
static

Definition at line 411 of file OctoMap.cpp.

◆ findEmptyNode()

std::unordered_set< octomap::OcTreeKey, octomap::OcTreeKey::KeyHash > rtabmap::OctoMap::findEmptyNode ( RtabmapColorOcTree octree_,
unsigned int  treeDepth,
octomap::point3d  startPosition 
)
static

Definition at line 494 of file OctoMap.cpp.

◆ floodFill()

void rtabmap::OctoMap::floodFill ( RtabmapColorOcTree octree_,
unsigned int  treeDepth,
octomap::point3d  startPosition,
std::unordered_set< octomap::OcTreeKey, octomap::OcTreeKey::KeyHash > &  EmptyNodes,
std::queue< octomap::point3d > &  positionToExplore 
)
static

Definition at line 474 of file OctoMap.cpp.

◆ getGridMax()

void rtabmap::OctoMap::getGridMax ( double &  x,
double &  y,
double &  z 
) const
inline

Definition at line 214 of file OctoMap.h.

◆ getGridMin()

void rtabmap::OctoMap::getGridMin ( double &  x,
double &  y,
double &  z 
) const
inline

Definition at line 213 of file OctoMap.h.

◆ hasColor()

bool rtabmap::OctoMap::hasColor ( ) const
inline

Definition at line 218 of file OctoMap.h.

◆ isNodeVisited()

bool rtabmap::OctoMap::isNodeVisited ( std::unordered_set< octomap::OcTreeKey, octomap::OcTreeKey::KeyHash > const &  EmptyNodes,
octomap::OcTreeKey const  key 
)
static

Definition at line 461 of file OctoMap.cpp.

◆ isValidEmpty()

bool rtabmap::OctoMap::isValidEmpty ( RtabmapColorOcTree octree_,
unsigned int  treeDepth,
octomap::point3d  startPosition 
)
static

Definition at line 397 of file OctoMap.cpp.

◆ octree()

const RtabmapColorOcTree* rtabmap::OctoMap::octree ( ) const
inline

Definition at line 190 of file OctoMap.h.

◆ setMaxRange()

void rtabmap::OctoMap::setMaxRange ( float  value)
inline

Definition at line 216 of file OctoMap.h.

◆ setRayTracing()

void rtabmap::OctoMap::setRayTracing ( bool  enabled)
inline

Definition at line 217 of file OctoMap.h.

◆ update()

bool rtabmap::OctoMap::update ( const std::map< int, Transform > &  poses)

Definition at line 512 of file OctoMap.cpp.

◆ updateMinMax()

void rtabmap::OctoMap::updateMinMax ( const octomap::point3d point)
private

Definition at line 1025 of file OctoMap.cpp.

◆ writeBinary()

bool rtabmap::OctoMap::writeBinary ( const std::string path)

Definition at line 1274 of file OctoMap.cpp.

Member Data Documentation

◆ addedNodes_

std::map<int, Transform> rtabmap::OctoMap::addedNodes_
private

Definition at line 234 of file OctoMap.h.

◆ cache_

std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > rtabmap::OctoMap::cache_
private

Definition at line 230 of file OctoMap.h.

◆ cacheClouds_

std::map<int, std::pair<const pcl::PointCloud<pcl::PointXYZRGB>::Ptr, const pcl::PointCloud<pcl::PointXYZRGB>::Ptr> > rtabmap::OctoMap::cacheClouds_
private

Definition at line 231 of file OctoMap.h.

◆ cacheViewPoints_

std::map<int, cv::Point3f> rtabmap::OctoMap::cacheViewPoints_
private

Definition at line 232 of file OctoMap.h.

◆ emptyFloodFillDepth_

unsigned int rtabmap::OctoMap::emptyFloodFillDepth_
private

Definition at line 240 of file OctoMap.h.

◆ fullUpdate_

bool rtabmap::OctoMap::fullUpdate_
private

Definition at line 236 of file OctoMap.h.

◆ hasColor_

bool rtabmap::OctoMap::hasColor_
private

Definition at line 235 of file OctoMap.h.

◆ maxValues_

double rtabmap::OctoMap::maxValues_[3]
private

Definition at line 242 of file OctoMap.h.

◆ minValues_

double rtabmap::OctoMap::minValues_[3]
private

Definition at line 241 of file OctoMap.h.

◆ octree_

RtabmapColorOcTree* rtabmap::OctoMap::octree_
private

Definition at line 233 of file OctoMap.h.

◆ rangeMax_

float rtabmap::OctoMap::rangeMax_
private

Definition at line 238 of file OctoMap.h.

◆ rayTracing_

bool rtabmap::OctoMap::rayTracing_
private

Definition at line 239 of file OctoMap.h.

◆ updateError_

float rtabmap::OctoMap::updateError_
private

Definition at line 237 of file OctoMap.h.


The documentation for this class was generated from the following files:


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:39:00