#include <OctoMap.h>
|
virtual 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) |
|
virtual unsigned long | getMemoryUsed () const |
|
bool | hasColor () const |
|
| OctoMap (const LocalGridCache *cache, const ParametersMap ¶meters=ParametersMap()) |
|
const RtabmapColorOcTree * | octree () const |
|
bool | writeBinary (const std::string &path) |
|
virtual | ~OctoMap () |
|
const std::map< int, Transform > & | addedNodes () const |
|
float | getCellSize () const |
|
void | getGridMax (double &x, double &y) const |
|
void | getGridMax (double &x, double &y, double &z) const |
|
void | getGridMin (double &x, double &y) const |
|
void | getGridMin (double &x, double &y, double &z) const |
|
float | getUpdateError () const |
|
bool | update (const std::map< int, Transform > &poses) |
|
virtual | ~GlobalMap () |
|
|
static octomap::point3d | findCloseEmpty (RtabmapColorOcTree *octree_, unsigned int treeDepth, octomap::point3d startPosition) |
|
static std::unordered_set< octomap::OcTreeKey, octomap::OcTreeKey::KeyHash > | findEmptyNode (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) |
|
static float | logodds (double probability) |
|
static double | probability (double logodds) |
|
Definition at line 175 of file global_map/OctoMap.h.
◆ OctoMap()
◆ ~OctoMap()
rtabmap::OctoMap::~OctoMap |
( |
| ) |
|
|
virtual |
◆ assemble()
void rtabmap::OctoMap::assemble |
( |
const std::list< std::pair< int, Transform > > & |
newPoses | ) |
|
|
protectedvirtual |
◆ clear()
void rtabmap::OctoMap::clear |
( |
| ) |
|
|
virtual |
◆ 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 |
◆ createProjectionMap()
cv::Mat rtabmap::OctoMap::createProjectionMap |
( |
float & |
xMin, |
|
|
float & |
yMin, |
|
|
float & |
gridCellSize, |
|
|
float |
minGridSize = 0.0f , |
|
|
unsigned int |
treeDepth = 0 |
|
) |
| |
◆ findCloseEmpty()
octomap::point3d rtabmap::OctoMap::findCloseEmpty |
( |
RtabmapColorOcTree * |
octree_, |
|
|
unsigned int |
treeDepth, |
|
|
octomap::point3d |
startPosition |
|
) |
| |
|
static |
◆ findEmptyNode()
std::unordered_set< octomap::OcTreeKey, octomap::OcTreeKey::KeyHash > rtabmap::OctoMap::findEmptyNode |
( |
RtabmapColorOcTree * |
octree_, |
|
|
unsigned int |
treeDepth, |
|
|
octomap::point3d |
startPosition |
|
) |
| |
|
static |
◆ 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 |
◆ getMemoryUsed()
unsigned long rtabmap::OctoMap::getMemoryUsed |
( |
| ) |
const |
|
virtual |
◆ hasColor()
bool rtabmap::OctoMap::hasColor |
( |
| ) |
const |
|
inline |
◆ isNodeVisited()
bool rtabmap::OctoMap::isNodeVisited |
( |
std::unordered_set< octomap::OcTreeKey, octomap::OcTreeKey::KeyHash > const & |
EmptyNodes, |
|
|
octomap::OcTreeKey const |
key |
|
) |
| |
|
static |
◆ isValidEmpty()
bool rtabmap::OctoMap::isValidEmpty |
( |
RtabmapColorOcTree * |
octree_, |
|
|
unsigned int |
treeDepth, |
|
|
octomap::point3d |
startPosition |
|
) |
| |
|
static |
◆ octree()
◆ updateMinMax()
void rtabmap::OctoMap::updateMinMax |
( |
const octomap::point3d & |
point | ) |
|
|
private |
◆ writeBinary()
bool rtabmap::OctoMap::writeBinary |
( |
const std::string & |
path | ) |
|
◆ emptyFloodFillDepth_
unsigned int rtabmap::OctoMap::emptyFloodFillDepth_ |
|
private |
◆ hasColor_
bool rtabmap::OctoMap::hasColor_ |
|
private |
◆ octree_
◆ rangeMax_
float rtabmap::OctoMap::rangeMax_ |
|
private |
◆ rayTracing_
bool rtabmap::OctoMap::rayTracing_ |
|
private |
The documentation for this class was generated from the following files: