#include <LocalGridMaker.h>
|
| void | createLocalMap (const LaserScan &cloud, const Transform &pose, cv::Mat &groundCells, cv::Mat &obstacleCells, cv::Mat &emptyCells, cv::Point3f &viewPointInOut) const |
| |
| void | createLocalMap (const Signature &node, cv::Mat &groundCells, cv::Mat &obstacleCells, cv::Mat &emptyCells, cv::Point3f &viewPoint) |
| |
| float | getCellSize () const |
| |
| bool | isGridFromDepth () const |
| |
| bool | isMapFrameProjection () const |
| |
| | LocalGridMaker (const ParametersMap ¶meters=ParametersMap()) |
| |
| virtual void | parseParameters (const ParametersMap ¶meters) |
| |
| template<typename PointT > |
| pcl::PointCloud< PointT >::Ptr | segmentCloud (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &pose, const cv::Point3f &viewPoint, pcl::IndicesPtr &groundIndices, pcl::IndicesPtr &obstaclesIndices, pcl::IndicesPtr *flatObstacles=0) const |
| |
| virtual | ~LocalGridMaker () |
| |
Definition at line 42 of file LocalGridMaker.h.
◆ LocalGridMaker()
◆ ~LocalGridMaker()
| rtabmap::LocalGridMaker::~LocalGridMaker |
( |
| ) |
|
|
virtual |
◆ createLocalMap() [1/2]
| void rtabmap::LocalGridMaker::createLocalMap |
( |
const LaserScan & |
cloud, |
|
|
const Transform & |
pose, |
|
|
cv::Mat & |
groundCells, |
|
|
cv::Mat & |
obstacleCells, |
|
|
cv::Mat & |
emptyCells, |
|
|
cv::Point3f & |
viewPointInOut |
|
) |
| const |
◆ createLocalMap() [2/2]
| void rtabmap::LocalGridMaker::createLocalMap |
( |
const Signature & |
node, |
|
|
cv::Mat & |
groundCells, |
|
|
cv::Mat & |
obstacleCells, |
|
|
cv::Mat & |
emptyCells, |
|
|
cv::Point3f & |
viewPoint |
|
) |
| |
◆ getCellSize()
| float rtabmap::LocalGridMaker::getCellSize |
( |
| ) |
const |
|
inline |
◆ isGridFromDepth()
| bool rtabmap::LocalGridMaker::isGridFromDepth |
( |
| ) |
const |
|
inline |
◆ isMapFrameProjection()
| bool rtabmap::LocalGridMaker::isMapFrameProjection |
( |
| ) |
const |
|
inline |
◆ parseParameters()
| void rtabmap::LocalGridMaker::parseParameters |
( |
const ParametersMap & |
parameters | ) |
|
|
virtual |
◆ segmentCloud()
template<typename PointT >
| pcl::PointCloud< PointT >::Ptr rtabmap::LocalGridMaker::segmentCloud |
( |
const typename pcl::PointCloud< PointT >::Ptr & |
cloud, |
|
|
const pcl::IndicesPtr & |
indices, |
|
|
const Transform & |
pose, |
|
|
const cv::Point3f & |
viewPoint, |
|
|
pcl::IndicesPtr & |
groundIndices, |
|
|
pcl::IndicesPtr & |
obstaclesIndices, |
|
|
pcl::IndicesPtr * |
flatObstacles = 0 |
|
) |
| const |
◆ cellSize_
| float rtabmap::LocalGridMaker::cellSize_ |
|
protected |
◆ cloudDecimation_
| unsigned int rtabmap::LocalGridMaker::cloudDecimation_ |
|
protected |
◆ clusterRadius_
| float rtabmap::LocalGridMaker::clusterRadius_ |
|
protected |
◆ flatObstaclesDetected_
| bool rtabmap::LocalGridMaker::flatObstaclesDetected_ |
|
protected |
◆ footprintHeight_
| float rtabmap::LocalGridMaker::footprintHeight_ |
|
protected |
◆ footprintLength_
| float rtabmap::LocalGridMaker::footprintLength_ |
|
protected |
◆ footprintWidth_
| float rtabmap::LocalGridMaker::footprintWidth_ |
|
protected |
◆ grid3D_
| bool rtabmap::LocalGridMaker::grid3D_ |
|
protected |
◆ groundIsObstacle_
| bool rtabmap::LocalGridMaker::groundIsObstacle_ |
|
protected |
◆ groundNormalsUp_
| float rtabmap::LocalGridMaker::groundNormalsUp_ |
|
protected |
◆ maxGroundAngle_
| float rtabmap::LocalGridMaker::maxGroundAngle_ |
|
protected |
◆ maxGroundHeight_
| float rtabmap::LocalGridMaker::maxGroundHeight_ |
|
protected |
◆ maxObstacleHeight_
| float rtabmap::LocalGridMaker::maxObstacleHeight_ |
|
protected |
◆ minClusterSize_
| int rtabmap::LocalGridMaker::minClusterSize_ |
|
protected |
◆ minGroundHeight_
| float rtabmap::LocalGridMaker::minGroundHeight_ |
|
protected |
◆ noiseFilteringMinNeighbors_
| int rtabmap::LocalGridMaker::noiseFilteringMinNeighbors_ |
|
protected |
◆ noiseFilteringRadius_
| float rtabmap::LocalGridMaker::noiseFilteringRadius_ |
|
protected |
◆ normalKSearch_
| int rtabmap::LocalGridMaker::normalKSearch_ |
|
protected |
◆ normalsSegmentation_
| bool rtabmap::LocalGridMaker::normalsSegmentation_ |
|
protected |
◆ occupancySensor_
| int rtabmap::LocalGridMaker::occupancySensor_ |
|
protected |
◆ parameters_
◆ preVoxelFiltering_
| bool rtabmap::LocalGridMaker::preVoxelFiltering_ |
|
protected |
◆ projMapFrame_
| bool rtabmap::LocalGridMaker::projMapFrame_ |
|
protected |
◆ rangeMax_
| float rtabmap::LocalGridMaker::rangeMax_ |
|
protected |
◆ rangeMin_
| float rtabmap::LocalGridMaker::rangeMin_ |
|
protected |
◆ rayTracing_
| bool rtabmap::LocalGridMaker::rayTracing_ |
|
protected |
◆ roiRatios_
| std::vector<float> rtabmap::LocalGridMaker::roiRatios_ |
|
protected |
◆ scan2dUnknownSpaceFilled_
| bool rtabmap::LocalGridMaker::scan2dUnknownSpaceFilled_ |
|
protected |
◆ scanDecimation_
| int rtabmap::LocalGridMaker::scanDecimation_ |
|
protected |
The documentation for this class was generated from the following files: