#include <OctoMap.h>
Public Member Functions | |
const std::map< int, Transform > & | addedNodes () const |
void | addToCache (int nodeId, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &ground, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &obstacles) |
void | clear () |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr | createCloud (unsigned int treeDepth=0, std::vector< int > *obstacleIndices=0, std::vector< int > *emptyIndices=0) const |
cv::Mat | createProjectionMap (float &xMin, float &yMin, float &gridCellSize, float minGridSize) |
OctoMap (float voxelSize=0.1f) | |
const octomap::ColorOcTree * | octree () const |
void | update (const std::map< int, Transform > &poses) |
bool | writeBinary (const std::string &path) |
virtual | ~OctoMap () |
Private Attributes | |
std::map< int, Transform > | addedNodes_ |
std::map< int, std::pair < pcl::PointCloud < pcl::PointXYZRGB >::Ptr, pcl::PointCloud < pcl::PointXYZRGB >::Ptr > > | cache_ |
octomap::KeyRay | keyRay_ |
std::map < octomap::ColorOcTreeNode *, OcTreeNodeInfo > | occupiedCells_ |
octomap::ColorOcTree * | octree_ |
rtabmap::OctoMap::OctoMap | ( | float | voxelSize = 0.1f | ) |
Definition at line 37 of file OctoMap.cpp.
rtabmap::OctoMap::~OctoMap | ( | ) | [virtual] |
Definition at line 43 of file OctoMap.cpp.
const std::map<int, Transform>& rtabmap::OctoMap::addedNodes | ( | ) | const [inline] |
void rtabmap::OctoMap::addToCache | ( | int | nodeId, |
pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | ground, | ||
pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | obstacles | ||
) |
Definition at line 58 of file OctoMap.cpp.
void rtabmap::OctoMap::clear | ( | ) |
Definition at line 49 of file OctoMap.cpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr rtabmap::OctoMap::createCloud | ( | unsigned int | treeDepth = 0 , |
std::vector< int > * | obstacleIndices = 0 , |
||
std::vector< int > * | emptyIndices = 0 |
||
) | const |
Definition at line 352 of file OctoMap.cpp.
cv::Mat rtabmap::OctoMap::createProjectionMap | ( | float & | xMin, |
float & | yMin, | ||
float & | gridCellSize, | ||
float | minGridSize | ||
) |
Definition at line 440 of file OctoMap.cpp.
const octomap::ColorOcTree* rtabmap::OctoMap::octree | ( | ) | const [inline] |
void rtabmap::OctoMap::update | ( | const std::map< int, Transform > & | poses | ) |
Definition at line 66 of file OctoMap.cpp.
bool rtabmap::OctoMap::writeBinary | ( | const std::string & | path | ) |
Definition at line 506 of file OctoMap.cpp.
std::map<int, Transform> rtabmap::OctoMap::addedNodes_ [private] |
std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> > rtabmap::OctoMap::cache_ [private] |
octomap::KeyRay rtabmap::OctoMap::keyRay_ [private] |
std::map<octomap::ColorOcTreeNode*, OcTreeNodeInfo> rtabmap::OctoMap::occupiedCells_ [private] |
octomap::ColorOcTree* rtabmap::OctoMap::octree_ [private] |