#include <OctoMap.h>
|
| 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 ¶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) |
| |
| bool | update (const std::map< int, Transform > &poses) |
| |
| bool | writeBinary (const std::string &path) |
| |
| virtual | ~OctoMap () |
| |
Definition at line 170 of file OctoMap.h.
| rtabmap::OctoMap::OctoMap |
( |
float |
cellSize = 0.1f, |
|
|
float |
occupancyThr = 0.5f, |
|
|
bool |
fullUpdate = false, |
|
|
float |
updateError = 0.01f |
|
) |
| |
| rtabmap::OctoMap::~OctoMap |
( |
| ) |
|
|
virtual |
| 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 |
|
) |
| |
| void rtabmap::OctoMap::addToCache |
( |
int |
nodeId, |
|
|
const cv::Mat & |
ground, |
|
|
const cv::Mat & |
obstacles, |
|
|
const cv::Mat & |
empty, |
|
|
const cv::Point3f & |
viewPoint |
|
) |
| |
| void rtabmap::OctoMap::clear |
( |
| ) |
|
| 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 |
| cv::Mat rtabmap::OctoMap::createProjectionMap |
( |
float & |
xMin, |
|
|
float & |
yMin, |
|
|
float & |
gridCellSize, |
|
|
float |
minGridSize = 0.0f, |
|
|
unsigned int |
treeDepth = 0 |
|
) |
| |
| 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::setMaxRange |
( |
float |
value | ) |
|
|
inline |
| void rtabmap::OctoMap::setRayTracing |
( |
bool |
enabled | ) |
|
|
inline |
| bool rtabmap::OctoMap::update |
( |
const std::map< int, Transform > & |
poses | ) |
|
| bool rtabmap::OctoMap::writeBinary |
( |
const std::string & |
path | ) |
|
| 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 |
| double rtabmap::OctoMap::maxValues_[3] |
|
private |
| double rtabmap::OctoMap::minValues_[3] |
|
private |
| float rtabmap::OctoMap::rangeMax_ |
|
private |
| bool rtabmap::OctoMap::rayTracing_ |
|
private |
| float rtabmap::OctoMap::updateError_ |
|
private |
The documentation for this class was generated from the following files: