#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) 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 ¶meters) | |
| OctoMap (float cellSize=0.1f, float occupancyThr=0.5f, bool fullUpdate=false, float updateError=0.01f) | |
| const RtabmapColorOcTree * | octree () const |
| void | setMaxRange (float value) |
| void | setRayTracing (bool enabled) |
| void | update (const std::map< int, Transform > &poses) |
| bool | writeBinary (const std::string &path) |
| virtual | ~OctoMap () |
Static Public Member Functions | |
| static void | HSVtoRGB (float *r, float *g, float *b, float h, float s, float v) |
Private Member Functions | |
| void | updateMinMax (const octomap::point3d &point) |
Private Attributes | |
| std::map< int, Transform > | addedNodes_ |
| 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_ |
| bool | fullUpdate_ |
| bool | hasColor_ |
| octomap::KeyRay | keyRay_ |
| double | maxValues_ [3] |
| double | minValues_ [3] |
| RtabmapColorOcTree * | octree_ |
| float | rangeMax_ |
| bool | rayTracing_ |
| float | updateError_ |
| rtabmap::OctoMap::OctoMap | ( | const ParametersMap & | parameters | ) |
Definition at line 265 of file OctoMap.cpp.
| rtabmap::OctoMap::OctoMap | ( | float | cellSize = 0.1f, |
| float | occupancyThr = 0.5f, |
||
| bool | fullUpdate = false, |
||
| float | updateError = 0.01f |
||
| ) |
Definition at line 309 of file OctoMap.cpp.
| rtabmap::OctoMap::~OctoMap | ( | ) | [virtual] |
Definition at line 324 of file OctoMap.cpp.
| const std::map<int, Transform>& rtabmap::OctoMap::addedNodes | ( | ) | const [inline] |
| 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 343 of file OctoMap.cpp.
| 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 353 of file OctoMap.cpp.
| void rtabmap::OctoMap::clear | ( | ) |
Definition at line 330 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, |
||
| std::vector< int > * | groundIndices = 0, |
||
| bool | originalRefPoints = true |
||
| ) | const |
Definition at line 920 of file OctoMap.cpp.
| cv::Mat rtabmap::OctoMap::createProjectionMap | ( | float & | xMin, |
| float & | yMin, | ||
| float & | gridCellSize, | ||
| float | minGridSize = 0.0f, |
||
| unsigned int | treeDepth = 0 |
||
| ) |
Definition at line 1043 of file OctoMap.cpp.
| void rtabmap::OctoMap::getGridMax | ( | double & | x, |
| double & | y, | ||
| double & | z | ||
| ) | const [inline] |
| void rtabmap::OctoMap::getGridMin | ( | double & | x, |
| double & | y, | ||
| double & | z | ||
| ) | const [inline] |
| bool rtabmap::OctoMap::hasColor | ( | ) | const [inline] |
| void rtabmap::OctoMap::HSVtoRGB | ( | float * | r, |
| float * | g, | ||
| float * | b, | ||
| float | h, | ||
| float | s, | ||
| float | v | ||
| ) | [static] |
Definition at line 871 of file OctoMap.cpp.
| const RtabmapColorOcTree* rtabmap::OctoMap::octree | ( | ) | const [inline] |
| void rtabmap::OctoMap::setMaxRange | ( | float | value | ) | [inline] |
| void rtabmap::OctoMap::setRayTracing | ( | bool | enabled | ) | [inline] |
| void rtabmap::OctoMap::update | ( | const std::map< int, Transform > & | poses | ) |
Definition at line 367 of file OctoMap.cpp.
| void rtabmap::OctoMap::updateMinMax | ( | const octomap::point3d & | point | ) | [private] |
Definition at line 843 of file OctoMap.cpp.
| bool rtabmap::OctoMap::writeBinary | ( | const std::string & | path | ) |
Definition at line 1098 of file OctoMap.cpp.
std::map<int, Transform> rtabmap::OctoMap::addedNodes_ [private] |
std::map<int, std::pair<std::pair<cv::Mat, cv::Mat>, cv::Mat> > rtabmap::OctoMap::cache_ [private] |
std::map<int, std::pair<const pcl::PointCloud<pcl::PointXYZRGB>::Ptr, const pcl::PointCloud<pcl::PointXYZRGB>::Ptr> > rtabmap::OctoMap::cacheClouds_ [private] |
std::map<int, cv::Point3f> rtabmap::OctoMap::cacheViewPoints_ [private] |
bool rtabmap::OctoMap::fullUpdate_ [private] |
bool rtabmap::OctoMap::hasColor_ [private] |
octomap::KeyRay rtabmap::OctoMap::keyRay_ [private] |
double rtabmap::OctoMap::maxValues_[3] [private] |
double rtabmap::OctoMap::minValues_[3] [private] |
RtabmapColorOcTree* rtabmap::OctoMap::octree_ [private] |
float rtabmap::OctoMap::rangeMax_ [private] |
bool rtabmap::OctoMap::rayTracing_ [private] |
float rtabmap::OctoMap::updateError_ [private] |