Namespaces | Functions
util3d.hpp File Reference
#include <rtabmap/utilite/ULogger.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/random_sample.h>
#include <pcl/filters/passthrough.h>
#include <pcl/filters/filter.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/common/transforms.h>
#include <pcl/common/common.h>
#include <pcl/search/kdtree.h>
#include <pcl/features/normal_3d.h>
#include <pcl/segmentation/extract_clusters.h>
Include dependency graph for util3d.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  rtabmap
namespace  rtabmap::util3d

Functions

template<typename PointT >
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClusters (const typename pcl::PointCloud< PointT >::Ptr &cloud, float clusterTolerance, int minClusterSize, int maxClusterSize, int *biggestClusterIndex)
template<typename PointT >
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClusters (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0)
 Wrapper of the pcl::EuclideanClusterExtraction class.
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::extractNegativeIndices (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices)
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::normalFiltering (const typename pcl::PointCloud< PointT >::Ptr &cloud, float angleMax, const Eigen::Vector4f &normal, float radiusSearch, const Eigen::Vector4f &viewpoint)
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::normalFiltering (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, float radiusSearch, const Eigen::Vector4f &viewpoint)
 Given a normal and a maximum angle error, keep all points of the cloud respecting this normal.
template<typename PointT >
void rtabmap::util3d::occupancy2DFromCloud3D (const typename pcl::PointCloud< PointT >::Ptr &cloud, cv::Mat &ground, cv::Mat &obstacles, float cellSize, float groundNormalAngle, int minClusterSize)
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::passThrough (const typename pcl::PointCloud< PointT >::Ptr &cloud, const std::string &axis, float min, float max)
template<typename PointT >
void rtabmap::util3d::projectCloudOnXYPlane (typename pcl::PointCloud< PointT >::Ptr &cloud)
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::radiusFiltering (const typename pcl::PointCloud< PointT >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::radiusFiltering (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius)
 Wrapper of the pcl::RadiusOutlierRemoval class.
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::removeNaNFromPointCloud (const typename pcl::PointCloud< PointT >::Ptr &cloud)
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::removeNaNNormalsFromPointCloud (const typename pcl::PointCloud< PointT >::Ptr &cloud)
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::sampling (const typename pcl::PointCloud< PointT >::Ptr &cloud, int samples)
template<typename PointT >
void rtabmap::util3d::segmentObstaclesFromGround (const typename pcl::PointCloud< PointT >::Ptr &cloud, pcl::IndicesPtr &ground, pcl::IndicesPtr &obstacles, float normalRadiusSearch, float groundNormalAngle, int minClusterSize, bool segmentFlatObstacles)
template<typename PointT >
PointT rtabmap::util3d::transformPoint (const PointT &pt, const Transform &transform)
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::transformPointCloud (const typename pcl::PointCloud< PointT >::Ptr &cloud, const Transform &transform)
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::voxelize (const typename pcl::PointCloud< PointT >::Ptr &cloud, float voxelSize)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:43