Namespaces | Functions
util3d_filtering.cpp File Reference
#include "rtabmap/core/util3d_filtering.h"
#include <pcl/filters/extract_indices.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/frustum_culling.h>
#include <pcl/filters/random_sample.h>
#include <pcl/filters/passthrough.h>
#include <pcl/filters/crop_box.h>
#include <pcl/features/normal_3d_omp.h>
#include <pcl/search/kdtree.h>
#include <pcl/common/common.h>
#include <pcl/segmentation/extract_clusters.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <rtabmap/core/util3d.h>
#include <rtabmap/core/util3d_surface.h>
#include <rtabmap/utilite/ULogger.h>
#include <rtabmap/utilite/UMath.h>
#include <rtabmap/utilite/UConversion.h>
Include dependency graph for util3d_filtering.cpp:

Go to the source code of this file.

Namespaces

 rtabmap
 
 rtabmap::util3d
 

Functions

LaserScan RTABMAP_EXP rtabmap::util3d::commonFiltering (const LaserScan &scan, int downsamplingStep, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalK=0, float normalRadius=0.0f, bool forceGroundNormalsUp=false)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::cropBox (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::cropBox (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::cropBox (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::cropBox (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false)
 
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP rtabmap::util3d::cropBox (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false)
 
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP rtabmap::util3d::cropBox (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP rtabmap::util3d::cropBox (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false)
 
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP rtabmap::util3d::cropBox (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false)
 
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::cropBoxImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform, bool negative)
 
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::cropBoxImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform, bool negative)
 
LaserScan RTABMAP_EXP rtabmap::util3d::downsample (const LaserScan &cloud, int step)
 
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP rtabmap::util3d::downsample (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int step)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP rtabmap::util3d::downsample (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, int step)
 
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP rtabmap::util3d::downsample (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, int step)
 
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP rtabmap::util3d::downsample (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, int step)
 
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::downsampleImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, int step)
 
std::vector< pcl::IndicesPtr > RTABMAP_EXP rtabmap::util3d::extractClusters (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0)
 
std::vector< pcl::IndicesPtr > RTABMAP_EXP rtabmap::util3d::extractClusters (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0)
 
std::vector< pcl::IndicesPtr > RTABMAP_EXP rtabmap::util3d::extractClusters (const pcl::PointCloud< pcl::PointXYZ >::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. More...
 
std::vector< pcl::IndicesPtr > RTABMAP_EXP rtabmap::util3d::extractClusters (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0)
 
std::vector< pcl::IndicesPtr > RTABMAP_EXP rtabmap::util3d::extractClusters (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0)
 
std::vector< pcl::IndicesPtr > RTABMAP_EXP rtabmap::util3d::extractClusters (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0)
 
template<typename PointT >
std::vector< pcl::IndicesPtr > rtabmap::util3d::extractClustersImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float clusterTolerance, int minClusterSize, int maxClusterSize, int *biggestClusterIndex)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::extractIndices (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::extractIndices (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::extractIndices (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::extractIndices (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative)
 
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP rtabmap::util3d::extractIndices (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP rtabmap::util3d::extractIndices (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized)
 
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP rtabmap::util3d::extractIndices (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized)
 
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::extractIndicesImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative)
 
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::extractIndicesImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative, bool keepOrganized)
 
pcl::IndicesPtr rtabmap::util3d::extractPlane (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float distanceThreshold, int maxIterations=100, pcl::ModelCoefficients *coefficientsOut=0)
 
pcl::IndicesPtr rtabmap::util3d::extractPlane (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float distanceThreshold, int maxIterations=100, pcl::ModelCoefficients *coefficientsOut=0)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::frustumFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &cameraPose, float horizontalFOV, float verticalFOV, float nearClipPlaneDistance, float farClipPlaneDistance, bool negative=false)
 
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP rtabmap::util3d::frustumFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &cameraPose, float horizontalFOV, float verticalFOV, float nearClipPlaneDistance, float farClipPlaneDistance, bool negative=false)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP rtabmap::util3d::frustumFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const Transform &cameraPose, float horizontalFOV, float verticalFOV, float nearClipPlaneDistance, float farClipPlaneDistance, bool negative=false)
 
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::frustumFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &cameraPose, float horizontalFOV, float verticalFOV, float nearClipPlaneDistance, float farClipPlaneDistance, bool negative)
 
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::frustumFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const Transform &cameraPose, float horizontalFOV, float verticalFOV, float nearClipPlaneDistance, float farClipPlaneDistance, bool negative)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::normalFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::normalFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::normalFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint)
 Given a normal and a maximum angle error, keep all points of the cloud respecting this normal. More...
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::normalFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::normalFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::normalFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint)
 
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::normalFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint)
 
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::normalFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float angleMax, const Eigen::Vector4f &normal)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::passThrough (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::passThrough (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::passThrough (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::passThrough (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::passThrough (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::passThrough (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
 
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP rtabmap::util3d::passThrough (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP rtabmap::util3d::passThrough (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false)
 
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_EXP rtabmap::util3d::passThrough (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false)
 
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP rtabmap::util3d::passThrough (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false)
 
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP rtabmap::util3d::passThrough (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false)
 
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_EXP rtabmap::util3d::passThrough (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const std::string &axis, float min, float max, bool negative=false)
 
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::passThroughImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative)
 
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::passThroughImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const std::string &axis, float min, float max, bool negative)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::radiusFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::radiusFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::radiusFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::radiusFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::radiusFiltering (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius)
 Wrapper of the pcl::RadiusOutlierRemoval class. More...
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::radiusFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::radiusFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::radiusFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius)
 
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::radiusFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float radiusSearch, int minNeighborsInRadius)
 
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP rtabmap::util3d::randomSampling (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int samples)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP rtabmap::util3d::randomSampling (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, int samples)
 
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::randomSamplingImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, int samples)
 
LaserScan RTABMAP_EXP rtabmap::util3d::rangeFiltering (const LaserScan &scan, float rangeMin, float rangeMax)
 
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP rtabmap::util3d::removeNaNFromPointCloud (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP rtabmap::util3d::removeNaNFromPointCloud (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud)
 
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::removeNaNFromPointCloudImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud)
 
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP rtabmap::util3d::removeNaNNormalsFromPointCloud (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
 
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP rtabmap::util3d::removeNaNNormalsFromPointCloud (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud)
 
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::removeNaNNormalsFromPointCloudImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::subtractAdaptiveFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearchRatio=0.01, int minNeighborsInRadius=1, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0))
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::subtractAdaptiveFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearchRatio=0.01, float maxAngle=M_PI/4.0f, int minNeighborsInRadius=1, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0))
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP rtabmap::util3d::subtractFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &substractCloud, float radiusSearch, int minNeighborsInRadius=1)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::subtractFiltering (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearch, int minNeighborsInRadius=1)
 
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP rtabmap::util3d::subtractFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::PointCloud< pcl::PointNormal >::Ptr &substractCloud, float radiusSearch, float maxAngle=M_PI/4.0f, int minNeighborsInRadius=1)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::subtractFiltering (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const pcl::PointCloud< pcl::PointNormal >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearch, float maxAngle=M_PI/4.0f, int minNeighborsInRadius=1)
 
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP rtabmap::util3d::subtractFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &substractCloud, float radiusSearch, float maxAngle=M_PI/4.0f, int minNeighborsInRadius=1)
 
pcl::IndicesPtr RTABMAP_EXP rtabmap::util3d::subtractFiltering (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearch, float maxAngle=M_PI/4.0f, int minNeighborsInRadius=1)
 
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::subtractFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const typename pcl::PointCloud< PointT >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearch, int minNeighborsInRadius)
 
template<typename PointT >
pcl::IndicesPtr rtabmap::util3d::subtractFilteringImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const typename pcl::PointCloud< PointT >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearch, float maxAngle, int minNeighborsInRadius)
 
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP rtabmap::util3d::voxelize (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
 
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP rtabmap::util3d::voxelize (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP rtabmap::util3d::voxelize (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
 
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP rtabmap::util3d::voxelize (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
 
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_EXP rtabmap::util3d::voxelize (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
 
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_EXP rtabmap::util3d::voxelize (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
 
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP rtabmap::util3d::voxelize (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float voxelSize)
 
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP rtabmap::util3d::voxelize (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, float voxelSize)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP rtabmap::util3d::voxelize (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float voxelSize)
 
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP rtabmap::util3d::voxelize (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, float voxelSize)
 
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_EXP rtabmap::util3d::voxelize (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, float voxelSize)
 
pcl::PointCloud< pcl::PointXYZINormal >::Ptr RTABMAP_EXP rtabmap::util3d::voxelize (const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, float voxelSize)
 
template<typename PointT >
pcl::PointCloud< PointT >::Ptr rtabmap::util3d::voxelizeImpl (const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
 


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:42