Point Cloud Library (PCL)
1.15.0-dev
|
Namespaces | |
detail | |
Classes | |
struct | AddPoints |
Simple kernel to add two points. More... | |
struct | AddCovariances |
Adds two matrices element-wise. More... | |
struct | convert_point_to_float3 |
Simple kernel to convert a PointXYZRGB to float3. More... | |
struct | ComputeCovarianceForPoint |
Kernel to compute a `‘covariance matrix’' for a single point. More... | |
class | OrganizedRadiusSearch |
Kernel to compute a radius neighborhood given a organized point cloud (aka range image cloud) More... | |
union | RGB |
Default RGB structure, defined as a union over 4 chars. More... | |
class | PCLCUDABase |
PCL base class. More... | |
struct | CovarianceMatrix |
misnamed class holding a 3x3 matrix More... | |
struct | OpenNIRGB |
Simple structure holding RGB data. More... | |
struct | Host |
Host helper class. More... | |
struct | Device |
Device helper class. More... | |
class | PointCloudAOS |
PointCloudAOS represents an AOS (Array of Structs) PointCloud implementation for CUDA processing. More... | |
class | PointCloudSOA |
PointCloudSOA represents a SOA (Struct of Arrays) PointCloud implementation for CUDA processing. More... | |
struct | PointIterator |
struct | PointIterator< Device, T > |
struct | PointIterator< Host, T > |
struct | StoragePointer |
struct | StoragePointer< Device, T > |
struct | StoragePointer< Host, T > |
struct | StorageAllocator |
struct | StorageAllocator< Device, T > |
struct | StorageAllocator< Host, T > |
struct | PointXYZRGB |
Default point xyz-rgb structure. More... | |
class | ScopeTimeCPU |
Class to measure the time spent in a scope. More... | |
class | ScopeTimeGPU |
Class to measure the time spent in a scope. More... | |
struct | NormalEstimationKernel |
struct | FastNormalEstimationKernel |
struct | NormalDeviationKernel |
struct | downsampleIndices |
struct | DebayerBilinear |
class | DebayeringDownsampling |
struct | YUV2RGBKernel |
class | YUV2RGB |
class | Debayering |
struct | ComputeXYZ |
Compute the XYZ values for a point based on disparity information. More... | |
struct | ComputeXYZRGB |
Compute the XYZ and RGB values for a point based on disparity information. More... | |
class | DisparityToCloud |
Disparity to PointCloudAOS generator. More... | |
struct | DisparityBoundSmoothing |
struct | DisparityClampedSmoothing |
struct | DisparityHelperMap |
struct | isNotZero |
struct | isInlier |
Check if a certain tuple is a point inlier. More... | |
struct | isNotInlier |
struct | SetColor |
struct | ChangeColor |
class | MultiRandomSampleConsensus |
RandomSampleConsensus represents an implementation of the RANSAC (RAndom SAmple Consensus) algorithm, as described in: "Random Sample Consensus: A Paradigm for Model Fitting with Applications to Image Analysis and Automated Cartography", Martin A. More... | |
class | RandomSampleConsensus |
RandomSampleConsensus represents an implementation of the RANSAC (RAndom SAmple Consensus) algorithm, as described in: "Random Sample Consensus: A Paradigm for Model Fitting with Applications to Image Analysis and Automated Cartography", Martin A. More... | |
class | SampleConsensus |
struct | DeleteIndices |
Check if a certain tuple is a point inlier. More... | |
struct | isNaNPoint |
class | SampleConsensusModel |
SampleConsensusModel represents the base model class. More... | |
struct | CountPlanarInlier |
Check if a certain tuple is a point inlier. More... | |
struct | NewCheckPlanarInlier |
Check if a certain tuple is a point inlier. More... | |
struct | CheckPlanarInlier |
Check if a certain tuple is a point inlier. More... | |
struct | CheckPlanarInlierIndices |
Check if a certain tuple is a point inlier. More... | |
struct | CheckPlanarInlierKinectNormalIndices |
Check if a certain tuple is a point inlier. More... | |
struct | CheckPlanarInlierKinectIndices |
Check if a certain tuple is a point inlier. More... | |
struct | CheckPlanarInlierNormalIndices |
Check if a certain tuple is a point inlier. More... | |
class | SampleConsensusModel1PointPlane |
SampleConsensusModel1PointPlane defines a model for 3D plane segmentation. More... | |
struct | Create1PointPlaneHypothesis |
Check if a certain tuple is a point inlier. More... | |
struct | Create1PointPlaneSampleHypothesis |
Check if a certain tuple is a point inlier. More... | |
struct | parallel_random_generator |
class | SampleConsensusModelPlane |
SampleConsensusModelPlane defines a model for 3D plane segmentation. More... | |
struct | CreatePlaneHypothesis |
Check if a certain tuple is a point inlier. More... | |
Functions | |
__host__ __device__ bool | isMuchSmallerThan (float x, float y) |
__host__ __device__ float3 | unitOrthogonal (const float3 &src) |
__host__ __device__ void | computeRoots2 (const float &b, const float &c, float3 &roots) |
__host__ __device__ void | swap (float &a, float &b) |
__host__ __device__ void | computeRoots (const CovarianceMatrix &m, float3 &roots) |
__host__ __device__ void | eigen33 (const CovarianceMatrix &mat, CovarianceMatrix &evecs, float3 &evals) |
template<class IteratorT > | |
void | compute3DCentroid (IteratorT begin, IteratorT end, float3 ¢roid) |
Computes a centroid for a given range of points. More... | |
template<class IteratorT > | |
void | computeCovariance (IteratorT begin, IteratorT end, CovarianceMatrix &cov, float3 centroid) |
Computes a covariance matrix for a given range of points. More... | |
struct | __align__ (16) PointXYZRGBNormal |
Default point xyz-rgb structure. More... | |
double | getTime () |
template<typename InputIteratorT , typename OutputIteratorT , template< typename > class Storage> | |
void | computePointNormals (InputIteratorT begin, InputIteratorT end, OutputIteratorT output, float focallength, const typename PointCloudAOS< Storage >::ConstPtr &input, float radius, int desired_number_neighbors) |
template<template< typename > class Storage, typename InputIteratorT > | |
shared_ptr< typename Storage< float4 >::type > | computePointNormals (InputIteratorT begin, InputIteratorT end, float focallength, const typename PointCloudAOS< Storage >::ConstPtr &input, float radius, int desired_number_neighbors) |
template<typename OutputIteratorT , template< typename > class Storage> | |
void | computeFastPointNormals (OutputIteratorT output, const typename PointCloudAOS< Storage >::ConstPtr &input) |
template<template< typename > class Storage> | |
shared_ptr< typename Storage< float4 >::type > | computeFastPointNormals (const typename PointCloudAOS< Storage >::ConstPtr &input) |
template<typename InputIteratorT , typename OutputIteratorT , template< typename > class Storage> | |
void | computeWeirdPointNormals (InputIteratorT begin, InputIteratorT end, OutputIteratorT output, float focallength, const typename PointCloudAOS< Storage >::ConstPtr &input, float radius, int desired_number_neighbors) |
template<template< typename > class Storage, typename InputIteratorT > | |
shared_ptr< typename Storage< float4 >::type > | computeWeirdPointNormals (InputIteratorT begin, InputIteratorT end, float focallength, const typename PointCloudAOS< Storage >::ConstPtr &input, float radius, int desired_number_neighbors) |
PCL_EXPORTS void | toPCL (const PointCloudAOS< Host > &input, const thrust::host_vector< float4 > &normals, pcl::PointCloud< pcl::PointXYZRGBNormal > &output) |
PCL_EXPORTS void | toPCL (const PointCloudAOS< Device > &input, const thrust::device_vector< float4 > &normals, pcl::PointCloud< pcl::PointXYZRGBNormal > &output) |
PCL_EXPORTS void | toPCL (const PointCloudAOS< Host > &input, pcl::PointCloud< pcl::PointXYZRGB > &output) |
PCL_EXPORTS void | toPCL (const PointCloudAOS< Device > &input, pcl::PointCloud< pcl::PointXYZRGB > &output) |
PCL_EXPORTS void | fromPCL (const pcl::PointCloud< pcl::PointXYZRGB > &input, PointCloudAOS< Host > &output) |
PCL_EXPORTS void | fromPCL (const pcl::PointCloud< pcl::PointXYZRGB > &input, PointCloudAOS< Device > &output) |
template<template< typename > class Storage, class DataT , class MaskT > | |
void | extractMask (const shared_ptr< typename Storage< DataT >::type > &input, MaskT *mask, shared_ptr< typename Storage< DataT >::type > &output) |
template<template< typename > class Storage, class T > | |
void | extractMask (const typename PointCloudAOS< Storage >::Ptr &input, T *mask, typename PointCloudAOS< Storage >::Ptr &output) |
template<template< typename > class Storage> | |
void | extractIndices (const typename PointCloudAOS< Storage >::Ptr &input, typename Storage< int >::type &indices, typename PointCloudAOS< Storage >::Ptr &output) |
template<template< typename > class Storage> | |
void | removeIndices (const typename PointCloudAOS< Storage >::Ptr &input, typename Storage< int >::type &indices, typename PointCloudAOS< Storage >::Ptr &output) |
template<template< typename > class Storage> | |
void | extractIndices (const typename PointCloudAOS< Storage >::Ptr &input, typename Storage< int >::type &indices, typename PointCloudAOS< Storage >::Ptr &output, const OpenNIRGB &color) |
template<template< typename > class Storage> | |
void | removeIndices (const typename PointCloudAOS< Storage >::Ptr &input, typename Storage< int >::type &indices, typename PointCloudAOS< Storage >::Ptr &output, const OpenNIRGB &color) |
template<template< typename > class Storage> | |
void | colorIndices (typename PointCloudAOS< Storage >::Ptr &input, shared_ptr< typename Storage< int >::type > indices, const OpenNIRGB &color) |
template<template< typename > class Storage> | |
void | colorCloud (typename PointCloudAOS< Storage >::Ptr &input, typename Storage< char4 >::type &colors) |
template<template< typename > class Storage, template< typename > class OtherStorage> | |
PointCloudAOS< OtherStorage >::Ptr | toStorage (const PointCloudAOS< Storage > &input) |
template<template< typename > class Storage> | |
void | toHost (const PointCloudAOS< Storage > &input, PointCloudAOS< Host > &output) |
template<template< typename > class Storage> | |
void | toDevice (const PointCloudAOS< Storage > &input, PointCloudAOS< Device > &output) |
template<template< typename > class Storage, typename OutT , typename InT > | |
void | createIndicesImage (OutT &dst, InT ®ion_mask) |
template<template< typename > class Storage, typename OutT , typename InT > | |
void | createNormalsImage (const OutT &dst, InT &normals) |
template<template< typename > class Storage> | |
void | markInliers (const typename PointCloudAOS< Storage >::ConstPtr &input, typename Storage< int >::type ®ion_mask, std::vector< shared_ptr< typename Storage< int >::type > > inlier_stencils) |
template<template< typename > class Storage> | |
std::vector< typename Storage< int >::type > | createRegionStencils (typename Storage< int >::type &parent, typename Storage< int >::type &rank, typename Storage< int >::type &size, int min_size, float percentage) |
PCL_EXPORTS void | meanShiftSegmentation (const cv::gpu::GpuMat &src, cv::Mat &dst, int sp, int sr, int minsize, detail::DjSets &comps, cv::TermCriteria criteria=cv::TermCriteria(cv::TermCriteria::MAX_ITER+cv::TermCriteria::EPS, 5, 1)) |
struct pcl::cuda::__align__ | ( | 16 | ) |
Default point xyz-rgb structure.
Definition at line 1 of file point_types.h.
void pcl::cuda::colorCloud | ( | typename PointCloudAOS< Storage >::Ptr & | input, |
typename Storage< char4 >::type & | colors | ||
) |
void pcl::cuda::colorIndices | ( | typename PointCloudAOS< Storage >::Ptr & | input, |
shared_ptr< typename Storage< int >::type > | indices, | ||
const OpenNIRGB & | color | ||
) |
void pcl::cuda::compute3DCentroid | ( | IteratorT | begin, |
IteratorT | end, | ||
float3 & | centroid | ||
) |
void pcl::cuda::computeCovariance | ( | IteratorT | begin, |
IteratorT | end, | ||
CovarianceMatrix & | cov, | ||
float3 | centroid | ||
) |
Computes a covariance matrix for a given range of points.
Definition at line 500 of file eigen.h.
References pcl::cuda::CovarianceMatrix::data.
shared_ptr<typename Storage<float4>::type> pcl::cuda::computeFastPointNormals | ( | const typename PointCloudAOS< Storage >::ConstPtr & | input | ) |
void pcl::cuda::computeFastPointNormals | ( | OutputIteratorT | output, |
const typename PointCloudAOS< Storage >::ConstPtr & | input | ||
) |
shared_ptr<typename Storage<float4>::type> pcl::cuda::computePointNormals | ( | InputIteratorT | begin, |
InputIteratorT | end, | ||
float | focallength, | ||
const typename PointCloudAOS< Storage >::ConstPtr & | input, | ||
float | radius, | ||
int | desired_number_neighbors | ||
) |
void pcl::cuda::computePointNormals | ( | InputIteratorT | begin, |
InputIteratorT | end, | ||
OutputIteratorT | output, | ||
float | focallength, | ||
const typename PointCloudAOS< Storage >::ConstPtr & | input, | ||
float | radius, | ||
int | desired_number_neighbors | ||
) |
|
inline |
Definition at line 164 of file eigen.h.
References computeRoots2(), pcl::cuda::CovarianceMatrix::data, and swap().
Referenced by eigen33().
|
inline |
Definition at line 143 of file eigen.h.
Referenced by computeRoots().
shared_ptr<typename Storage<float4>::type> pcl::cuda::computeWeirdPointNormals | ( | InputIteratorT | begin, |
InputIteratorT | end, | ||
float | focallength, | ||
const typename PointCloudAOS< Storage >::ConstPtr & | input, | ||
float | radius, | ||
int | desired_number_neighbors | ||
) |
void pcl::cuda::computeWeirdPointNormals | ( | InputIteratorT | begin, |
InputIteratorT | end, | ||
OutputIteratorT | output, | ||
float | focallength, | ||
const typename PointCloudAOS< Storage >::ConstPtr & | input, | ||
float | radius, | ||
int | desired_number_neighbors | ||
) |
void pcl::cuda::createIndicesImage | ( | OutT & | dst, |
InT & | region_mask | ||
) |
void pcl::cuda::createNormalsImage | ( | const OutT & | dst, |
InT & | normals | ||
) |
std::vector<typename Storage<int>::type> pcl::cuda::createRegionStencils | ( | typename Storage< int >::type & | parent, |
typename Storage< int >::type & | rank, | ||
typename Storage< int >::type & | size, | ||
int | min_size, | ||
float | percentage | ||
) |
|
inline |
Definition at line 227 of file eigen.h.
References computeRoots(), pcl::cuda::CovarianceMatrix::data, and unitOrthogonal().
Referenced by pcl::cuda::NormalEstimationKernel< Storage >::operator()().
void pcl::cuda::extractIndices | ( | const typename PointCloudAOS< Storage >::Ptr & | input, |
typename Storage< int >::type & | indices, | ||
typename PointCloudAOS< Storage >::Ptr & | output | ||
) |
void pcl::cuda::extractIndices | ( | const typename PointCloudAOS< Storage >::Ptr & | input, |
typename Storage< int >::type & | indices, | ||
typename PointCloudAOS< Storage >::Ptr & | output, | ||
const OpenNIRGB & | color | ||
) |
void pcl::cuda::extractMask | ( | const shared_ptr< typename Storage< DataT >::type > & | input, |
MaskT * | mask, | ||
shared_ptr< typename Storage< DataT >::type > & | output | ||
) |
void pcl::cuda::extractMask | ( | const typename PointCloudAOS< Storage >::Ptr & | input, |
T * | mask, | ||
typename PointCloudAOS< Storage >::Ptr & | output | ||
) |
PCL_EXPORTS void pcl::cuda::fromPCL | ( | const pcl::PointCloud< pcl::PointXYZRGB > & | input, |
PointCloudAOS< Device > & | output | ||
) |
PCL_EXPORTS void pcl::cuda::fromPCL | ( | const pcl::PointCloud< pcl::PointXYZRGB > & | input, |
PointCloudAOS< Host > & | output | ||
) |
|
inline |
Definition at line 112 of file time_cpu.h.
Referenced by pcl::cuda::ScopeTimeCPU::ScopeTimeCPU(), and pcl::cuda::ScopeTimeCPU::~ScopeTimeCPU().
|
inline |
Definition at line 102 of file eigen.h.
Referenced by unitOrthogonal().
void pcl::cuda::markInliers | ( | const typename PointCloudAOS< Storage >::ConstPtr & | input, |
typename Storage< int >::type & | region_mask, | ||
std::vector< shared_ptr< typename Storage< int >::type > > | inlier_stencils | ||
) |
PCL_EXPORTS void pcl::cuda::meanShiftSegmentation | ( | const cv::gpu::GpuMat & | src, |
cv::Mat & | dst, | ||
int | sp, | ||
int | sr, | ||
int | minsize, | ||
detail::DjSets & | comps, | ||
cv::TermCriteria | criteria = cv::TermCriteria(cv::TermCriteria::MAX_ITER+cv::TermCriteria::EPS, 5, 1) |
||
) |
void pcl::cuda::removeIndices | ( | const typename PointCloudAOS< Storage >::Ptr & | input, |
typename Storage< int >::type & | indices, | ||
typename PointCloudAOS< Storage >::Ptr & | output | ||
) |
void pcl::cuda::removeIndices | ( | const typename PointCloudAOS< Storage >::Ptr & | input, |
typename Storage< int >::type & | indices, | ||
typename PointCloudAOS< Storage >::Ptr & | output, | ||
const OpenNIRGB & | color | ||
) |
|
inline |
Definition at line 156 of file eigen.h.
Referenced by computeRoots().
void pcl::cuda::toDevice | ( | const PointCloudAOS< Storage > & | input, |
PointCloudAOS< Device > & | output | ||
) |
void pcl::cuda::toHost | ( | const PointCloudAOS< Storage > & | input, |
PointCloudAOS< Host > & | output | ||
) |
PCL_EXPORTS void pcl::cuda::toPCL | ( | const PointCloudAOS< Device > & | input, |
const thrust::device_vector< float4 > & | normals, | ||
pcl::PointCloud< pcl::PointXYZRGBNormal > & | output | ||
) |
PCL_EXPORTS void pcl::cuda::toPCL | ( | const PointCloudAOS< Device > & | input, |
pcl::PointCloud< pcl::PointXYZRGB > & | output | ||
) |
PCL_EXPORTS void pcl::cuda::toPCL | ( | const PointCloudAOS< Host > & | input, |
const thrust::host_vector< float4 > & | normals, | ||
pcl::PointCloud< pcl::PointXYZRGBNormal > & | output | ||
) |
PCL_EXPORTS void pcl::cuda::toPCL | ( | const PointCloudAOS< Host > & | input, |
pcl::PointCloud< pcl::PointXYZRGB > & | output | ||
) |
PointCloudAOS<OtherStorage>::Ptr pcl::cuda::toStorage | ( | const PointCloudAOS< Storage > & | input | ) |
|
inline |