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

#include <OctoMap.h>

Inheritance diagram for rtabmap::OctoMap:
Inheritance graph
[legend]

Public Member Functions

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 &parameters=ParametersMap())
 
const RtabmapColorOcTreeoctree () const
 
bool writeBinary (const std::string &path)
 
virtual ~OctoMap ()
 
- Public Member Functions inherited from rtabmap::GlobalMap
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 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)
 
- Static Public Member Functions inherited from rtabmap::GlobalMap
static float logodds (double probability)
 
static double probability (double logodds)
 

Protected Member Functions

virtual void assemble (const std::list< std::pair< int, Transform > > &newPoses)
 
- Protected Member Functions inherited from rtabmap::GlobalMap
void addAssembledNode (int id, const Transform &pose)
 
const std::map< int, Transform > & assembledNodes () const
 
const std::map< int, LocalGrid > & cache () const
 
 GlobalMap (const LocalGridCache *cache, const ParametersMap &parameters=ParametersMap())
 
bool isNodeAssembled (int id)
 

Private Member Functions

void updateMinMax (const octomap::point3d &point)
 

Private Attributes

unsigned int emptyFloodFillDepth_
 
bool hasColor_
 
RtabmapColorOcTreeoctree_
 
float rangeMax_
 
bool rayTracing_
 

Additional Inherited Members

- Protected Attributes inherited from rtabmap::GlobalMap
float cellSize_
 
float logOddsClampingMax_
 
float logOddsClampingMin_
 
float logOddsHit_
 
float logOddsMiss_
 
double maxValues_ [3]
 
double minValues_ [3]
 
float occupancyThr_
 
float updateError_
 

Detailed Description

Definition at line 175 of file global_map/OctoMap.h.

Constructor & Destructor Documentation

◆ OctoMap()

rtabmap::OctoMap::OctoMap ( const LocalGridCache cache,
const ParametersMap parameters = ParametersMap() 
)

Definition at line 291 of file OctoMap.cpp.

◆ ~OctoMap()

rtabmap::OctoMap::~OctoMap ( )
virtual

Definition at line 330 of file OctoMap.cpp.

Member Function Documentation

◆ assemble()

void rtabmap::OctoMap::assemble ( const std::list< std::pair< int, Transform > > &  newPoses)
protectedvirtual

Implements rtabmap::GlobalMap.

Definition at line 467 of file OctoMap.cpp.

◆ clear()

void rtabmap::OctoMap::clear ( )
virtual

Reimplemented from rtabmap::GlobalMap.

Definition at line 336 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 825 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 989 of file OctoMap.cpp.

◆ findCloseEmpty()

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

Definition at line 366 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 449 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 429 of file OctoMap.cpp.

◆ getMemoryUsed()

unsigned long rtabmap::OctoMap::getMemoryUsed ( ) const
virtual

Reimplemented from rtabmap::GlobalMap.

Definition at line 343 of file OctoMap.cpp.

◆ hasColor()

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

Definition at line 203 of file global_map/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 416 of file OctoMap.cpp.

◆ isValidEmpty()

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

Definition at line 352 of file OctoMap.cpp.

◆ octree()

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

Definition at line 179 of file global_map/OctoMap.h.

◆ updateMinMax()

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

Definition at line 796 of file OctoMap.cpp.

◆ writeBinary()

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

Definition at line 1045 of file OctoMap.cpp.

Member Data Documentation

◆ emptyFloodFillDepth_

unsigned int rtabmap::OctoMap::emptyFloodFillDepth_
private

Definition at line 222 of file global_map/OctoMap.h.

◆ hasColor_

bool rtabmap::OctoMap::hasColor_
private

Definition at line 219 of file global_map/OctoMap.h.

◆ octree_

RtabmapColorOcTree* rtabmap::OctoMap::octree_
private

Definition at line 218 of file global_map/OctoMap.h.

◆ rangeMax_

float rtabmap::OctoMap::rangeMax_
private

Definition at line 220 of file global_map/OctoMap.h.

◆ rayTracing_

bool rtabmap::OctoMap::rayTracing_
private

Definition at line 221 of file global_map/OctoMap.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jul 1 2024 02:42:45