Point Cloud Library (PCL)
1.15.0-dev
|
Namespaces | |
common | |
ComparisonOps | |
console | |
cuda | |
deprecated | |
detail | |
device | |
distances | |
experimental | |
face_detection | |
features | |
fields | |
filters | |
geometry | |
gpu | |
internal | |
io | |
ism | |
keypoints | |
kinfuLS | |
ndt2d | |
occlusion_reasoning | |
octree | |
outofcore | |
people | |
poisson | |
recognition | |
registration | |
search | |
segmentation | |
surface | |
test | |
test_macros.h provide helper macros for testing vectors, matrices etc. | |
texture_mapping | |
tracking | |
traits | |
utils | |
visualization | |
Classes | |
struct | PointXYZIEdge |
Point cloud containing edge information. More... | |
class | Convolution |
A 2D convolution class. More... | |
class | Edge |
class | kernel |
class | Keypoint |
Keypoint represents the base class for key points. More... | |
class | Morphology |
class | CloudIterator |
Iterator class for point clouds with or without given indices. More... | |
class | ConstCloudIterator |
Iterator class for point clouds with or without given indices. More... | |
class | BivariatePolynomialT |
This represents a bivariate polynomial and provides some functionality for it. More... | |
struct | NdCentroidFunctor |
Helper functor structure for n-D centroid estimation. More... | |
class | CentroidPoint |
A generic class that computes the centroid of points fed to it. More... | |
class | ColorLUT |
struct | NdConcatenateFunctor |
Helper functor structure for concatenate. More... | |
class | PointCloud |
PointCloud represents the base class in PCL for storing collections of 3D points. More... | |
class | FeatureHistogram |
Type for histograms for computing mean and variance of some floats. More... | |
class | GaussianKernel |
Class GaussianKernel assembles all the method for computing, convolving, smoothing, gradients computing an image using a gaussian kernel. More... | |
class | PCA |
Principal Component analysis (PCA) class. More... | |
class | PiecewiseLinearFunction |
This provides functionalities to efficiently return values for piecewise linear function. More... | |
class | PolynomialCalculationsT |
This provides some functionality for polynomials, like finding roots or approximating bivariate polynomials. More... | |
class | PosesFromMatches |
calculate 3D transformation based on point correspondences More... | |
class | Synchronizer |
/brief This template class synchronizes two data streams of different types. More... | |
class | StopWatch |
Simple stopwatch. More... | |
class | ScopeTime |
Class to measure the time spent in a scope. More... | |
class | EventFrequency |
A helper class to measure frequency of a certain event. More... | |
class | TimeTrigger |
Timer class that invokes registered callback methods periodically. More... | |
class | TransformationFromCorrespondences |
Calculates a transformation based on corresponding 3D points. More... | |
class | VectorAverage |
Calculates the weighted average and the covariance matrix. More... | |
struct | Correspondence |
Correspondence represents a match between two entities (e.g., points, descriptors, etc). More... | |
struct | PointCorrespondence3D |
Representation of a (possible) correspondence between two 3D points in two different coordinate frames (e.g. More... | |
struct | PointCorrespondence6D |
Representation of a (possible) correspondence between two points (e.g. More... | |
class | PCLException |
A base class for all pcl exceptions which inherits from std::runtime_error. More... | |
class | InvalidConversionException |
An exception that is thrown when a PCLPointCloud2 message cannot be converted into a PCL type. More... | |
class | IsNotDenseException |
An exception that is thrown when a PointCloud is not dense but is attempted to be used as dense. More... | |
class | InvalidSACModelTypeException |
An exception that is thrown when a sample consensus model doesn't have the correct number of samples defined in model_types.h. More... | |
class | IOException |
An exception that is thrown during an IO error (typical read/write errors) More... | |
class | InitFailedException |
An exception thrown when init can not be performed should be used in all the PCLBase class inheritants. More... | |
class | UnorganizedPointCloudException |
An exception that is thrown when an organized point cloud is needed but not provided. More... | |
class | KernelWidthTooSmallException |
An exception that is thrown when the kernel size is too small. More... | |
class | UnhandledPointTypeException |
class | ComputeFailedException |
class | BadArgumentException |
An exception that is thrown when the arguments number or type is wrong/unhandled. More... | |
struct | for_each_type_impl |
struct | for_each_type_impl< false > |
struct | intersect |
class | DefaultIterator |
class | IteratorIdx |
struct | _PointXYZ |
struct | PointXYZ |
A point structure representing Euclidean xyz coordinates. More... | |
struct | _RGB |
struct | RGB |
A structure representing RGB color information. More... | |
struct | _Intensity |
struct | Intensity |
A point structure representing the grayscale intensity in single-channel images. More... | |
struct | _Intensity8u |
struct | Intensity8u |
A point structure representing the grayscale intensity in single-channel images. More... | |
struct | _Intensity32u |
struct | Intensity32u |
A point structure representing the grayscale intensity in single-channel images. More... | |
struct | _PointXYZI |
A point structure representing Euclidean xyz coordinates, and the intensity value. More... | |
struct | PointXYZI |
struct | _PointXYZL |
struct | PointXYZL |
struct | Label |
struct | _PointXYZRGBA |
struct | PointXYZRGBA |
A point structure representing Euclidean xyz coordinates, and the RGBA color. More... | |
struct | _PointXYZRGB |
struct | _PointXYZRGBL |
struct | PointXYZRGB |
A point structure representing Euclidean xyz coordinates, and the RGB color. More... | |
struct | PointXYZRGBL |
struct | _PointXYZLAB |
struct | PointXYZLAB |
A point structure representing Euclidean xyz coordinates, and the CIELAB color. More... | |
struct | _PointXYZHSV |
struct | PointXYZHSV |
struct | PointXY |
A 2D point structure representing Euclidean xy coordinates. More... | |
struct | PointUV |
A 2D point structure representing pixel image coordinates. More... | |
struct | InterestPoint |
A point structure representing an interest point with Euclidean xyz coordinates, and an interest value. More... | |
struct | _Normal |
struct | Normal |
A point structure representing normal coordinates and the surface curvature estimate. More... | |
struct | _Axis |
struct | Axis |
A point structure representing an Axis using its normal coordinates. More... | |
struct | _PointNormal |
struct | PointNormal |
A point structure representing Euclidean xyz coordinates, together with normal coordinates and the surface curvature estimate. More... | |
struct | _PointXYZRGBNormal |
struct | PointXYZRGBNormal |
A point structure representing Euclidean xyz coordinates, and the RGB color, together with normal coordinates and the surface curvature estimate. More... | |
struct | _PointXYZINormal |
struct | PointXYZINormal |
A point structure representing Euclidean xyz coordinates, intensity, together with normal coordinates and the surface curvature estimate. More... | |
struct | _PointXYZLNormal |
struct | PointXYZLNormal |
A point structure representing Euclidean xyz coordinates, a label, together with normal coordinates and the surface curvature estimate. More... | |
struct | _PointWithRange |
struct | PointWithRange |
A point structure representing Euclidean xyz coordinates, padded with an extra range float. More... | |
struct | _PointWithViewpoint |
struct | PointWithViewpoint |
A point structure representing Euclidean xyz coordinates together with the viewpoint from which it was seen. More... | |
struct | MomentInvariants |
A point structure representing the three moment invariants. More... | |
struct | PrincipalRadiiRSD |
A point structure representing the minimum and maximum surface radii (in meters) computed using RSD. More... | |
struct | Boundary |
A point structure representing a description of whether a point is lying on a surface boundary or not. More... | |
struct | PrincipalCurvatures |
A point structure representing the principal curvatures and their magnitudes. More... | |
struct | PFHSignature125 |
A point structure representing the Point Feature Histogram (PFH). More... | |
struct | PFHRGBSignature250 |
A point structure representing the Point Feature Histogram with colors (PFHRGB). More... | |
struct | PPFSignature |
A point structure for storing the Point Pair Feature (PPF) values. More... | |
struct | CPPFSignature |
A point structure for storing the Point Pair Feature (CPPF) values. More... | |
struct | PPFRGBSignature |
A point structure for storing the Point Pair Color Feature (PPFRGB) values. More... | |
struct | NormalBasedSignature12 |
A point structure representing the Normal Based Signature for a feature matrix of 4-by-3. More... | |
struct | ShapeContext1980 |
A point structure representing a Shape Context. More... | |
struct | UniqueShapeContext1960 |
A point structure representing a Unique Shape Context. More... | |
struct | SHOT352 |
A point structure representing the generic Signature of Histograms of OrienTations (SHOT) - shape only. More... | |
struct | SHOT1344 |
A point structure representing the generic Signature of Histograms of OrienTations (SHOT) - shape+color. More... | |
struct | _ReferenceFrame |
A structure representing the Local Reference Frame of a point. More... | |
struct | ReferenceFrame |
struct | FPFHSignature33 |
A point structure representing the Fast Point Feature Histogram (FPFH). More... | |
struct | VFHSignature308 |
A point structure representing the Viewpoint Feature Histogram (VFH). More... | |
struct | GRSDSignature21 |
A point structure representing the Global Radius-based Surface Descriptor (GRSD). More... | |
struct | BRISKSignature512 |
A point structure representing the Binary Robust Invariant Scalable Keypoints (BRISK). More... | |
struct | ESFSignature640 |
A point structure representing the Ensemble of Shape Functions (ESF). More... | |
struct | GASDSignature512 |
A point structure representing the Globally Aligned Spatial Distribution (GASD) shape descriptor. More... | |
struct | GASDSignature984 |
A point structure representing the Globally Aligned Spatial Distribution (GASD) shape and color descriptor. More... | |
struct | GASDSignature7992 |
A point structure representing the Globally Aligned Spatial Distribution (GASD) shape and color descriptor. More... | |
struct | GFPFHSignature16 |
A point structure representing the GFPFH descriptor with 16 bins. More... | |
struct | Narf36 |
A point structure representing the Narf descriptor. More... | |
struct | BorderDescription |
A structure to store if a point in a range image lies on a border between an obstacle and the background. More... | |
struct | IntensityGradient |
A point structure representing the intensity gradient of an XYZI point cloud. More... | |
struct | Histogram |
A point structure representing an N-D histogram. More... | |
struct | _PointWithScale |
struct | PointWithScale |
A point structure representing a 3-D position and scale. More... | |
struct | _PointSurfel |
struct | PointSurfel |
A surfel, that is, a point structure representing Euclidean xyz coordinates, together with normal coordinates, a RGBA color, a radius, a confidence value and the surface curvature estimate. More... | |
struct | _PointDEM |
struct | PointDEM |
A point structure representing Digital Elevation Map. More... | |
struct | ModelCoefficients |
class | PCLBase |
PCL base class. More... | |
class | PCLBase< pcl::PCLPointCloud2 > |
struct | PCLHeader |
struct | PCLImage |
struct | PCLPointCloud2 |
struct | PCLPointField |
struct | FieldMatches |
struct | NdCopyEigenPointFunctor |
Helper functor structure for copying data between an Eigen type and a PointT. More... | |
struct | NdCopyPointEigenFunctor |
Helper functor structure for copying data between an Eigen type and a PointT. More... | |
class | PointRepresentation |
PointRepresentation provides a set of methods for converting a point structs/object into an n-dimensional vector. More... | |
class | DefaultPointRepresentation |
DefaultPointRepresentation extends PointRepresentation to define default behavior for common point types. More... | |
class | DefaultFeatureRepresentation |
DefaulFeatureRepresentation extends PointRepresentation and is intended to be used when defining the default behavior for feature descriptor types (i.e., copy each element of each field into a float array). More... | |
class | DefaultPointRepresentation< PointXYZ > |
class | DefaultPointRepresentation< PointXYZI > |
class | DefaultPointRepresentation< PointNormal > |
class | DefaultPointRepresentation< PFHSignature125 > |
class | DefaultPointRepresentation< PFHRGBSignature250 > |
class | DefaultPointRepresentation< PPFSignature > |
class | DefaultPointRepresentation< FPFHSignature33 > |
class | DefaultPointRepresentation< VFHSignature308 > |
class | DefaultPointRepresentation< GASDSignature512 > |
class | DefaultPointRepresentation< GASDSignature984 > |
class | DefaultPointRepresentation< GASDSignature7992 > |
class | DefaultPointRepresentation< Narf36 > |
class | DefaultPointRepresentation< NormalBasedSignature12 > |
class | DefaultPointRepresentation< ShapeContext1980 > |
class | DefaultPointRepresentation< UniqueShapeContext1960 > |
class | DefaultPointRepresentation< SHOT352 > |
class | DefaultPointRepresentation< SHOT1344 > |
class | CustomPointRepresentation |
CustomPointRepresentation extends PointRepresentation to allow for sub-part selection on the point. More... | |
struct | PointIndices |
struct | PolygonMesh |
class | BearingAngleImage |
class BearingAngleImage is used as an interface to generate Bearing Angle(BA) image. More... | |
class | RangeImage |
RangeImage is derived from pcl/PointCloud and provides functionalities with focus on situations where a 3D scene was captured from a specific view point. More... | |
class | RangeImagePlanar |
RangeImagePlanar is derived from the original range image and differs from it because it's not a spherical projection, but using a projection plane (as normal cameras do), therefore being better applicable for range sensors that already provide a range image by themselves (stereo cameras, ToF-cameras), so that a conversion to point cloud and then to a spherical range image becomes unnecessary. More... | |
class | RangeImageSpherical |
RangeImageSpherical is derived from the original range image and uses a slightly different spherical projection. More... | |
struct | TexMaterial |
struct | TextureMesh |
struct | CopyIfFieldExists |
A helper functor that can copy a specific value if the given field exists. More... | |
struct | SetIfFieldExists |
A helper functor that can set a specific value in a field if the field exists. More... | |
struct | has_custom_allocator |
Tests at compile time if type T has a custom allocator. More... | |
struct | Vertices |
Describes a set of vertices in a polygon mesh, by basically storing an array of indices. More... | |
class | OrganizedNeighborSearch |
OrganizedNeighborSearch class More... | |
class | ShapeContext3DEstimation |
ShapeContext3DEstimation implements the 3D shape context descriptor as described in: More... | |
class | BOARDLocalReferenceFrameEstimation |
BOARDLocalReferenceFrameEstimation implements the BOrder Aware Repeatable Directions algorithm for local reference frame estimation as described here: More... | |
class | BoundaryEstimation |
BoundaryEstimation estimates whether a set of points is lying on surface boundaries using an angle criterion. More... | |
class | BRISK2DEstimation |
Implementation of the BRISK-descriptor, based on the original code and paper reference by. More... | |
class | CPPFEstimation |
Class that calculates the "surflet" features for each pair in the given pointcloud. More... | |
class | CRHEstimation |
CRHEstimation estimates the Camera Roll Histogram (CRH) descriptor for a given point cloud dataset containing XYZ data and normals, as presented in: More... | |
class | CVFHEstimation |
CVFHEstimation estimates the Clustered Viewpoint Feature Histogram (CVFH) descriptor for a given point cloud dataset containing XYZ data and normals, as presented in: More... | |
class | DifferenceOfNormalsEstimation |
A Difference of Normals (DoN) scale filter implementation for point cloud data. More... | |
class | ESFEstimation |
ESFEstimation estimates the ensemble of shape functions descriptors for a given point cloud dataset containing points. More... | |
class | Feature |
Feature represents the base feature class. More... | |
class | FeatureFromNormals |
class | FeatureFromLabels |
class | FeatureWithLocalReferenceFrames |
FeatureWithLocalReferenceFrames provides a public interface for descriptor extractor classes which need a local reference frame at each input keypoint. More... | |
class | FLARELocalReferenceFrameEstimation |
FLARELocalReferenceFrameEstimation implements the Fast LocAl Reference framE algorithm for local reference frame estimation as described here: More... | |
class | FPFHEstimation |
FPFHEstimation estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset containing points and normals. More... | |
class | FPFHEstimationOMP |
FPFHEstimationOMP estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset containing points and normals, in parallel, using the OpenMP standard. More... | |
class | GASDEstimation |
GASDEstimation estimates the Globally Aligned Spatial Distribution (GASD) descriptor for a given point cloud dataset given XYZ data. More... | |
class | GASDColorEstimation |
GASDColorEstimation estimates the Globally Aligned Spatial Distribution (GASD) descriptor for a given point cloud dataset given XYZ and RGB data. More... | |
class | GFPFHEstimation |
GFPFHEstimation estimates the Global Fast Point Feature Histogram (GFPFH) descriptor for a given point cloud dataset containing points and labels. More... | |
class | GRSDEstimation |
GRSDEstimation estimates the Global Radius-based Surface Descriptor (GRSD) for a given point cloud dataset containing points and normals. More... | |
struct | IntegralImageTypeTraits |
struct | IntegralImageTypeTraits< float > |
struct | IntegralImageTypeTraits< char > |
struct | IntegralImageTypeTraits< short > |
struct | IntegralImageTypeTraits< unsigned short > |
struct | IntegralImageTypeTraits< unsigned char > |
struct | IntegralImageTypeTraits< int > |
struct | IntegralImageTypeTraits< unsigned int > |
class | IntegralImage2D |
Determines an integral image representation for a given organized data array. More... | |
class | IntegralImage2D< DataType, 1 > |
partial template specialization for integral images with just one channel. More... | |
class | IntegralImageNormalEstimation |
Surface normal estimation on organized data using integral images. More... | |
class | IntensityGradientEstimation |
IntensityGradientEstimation estimates the intensity gradient for a point cloud that contains position and intensity values. More... | |
class | IntensitySpinEstimation |
IntensitySpinEstimation estimates the intensity-domain spin image descriptors for a given point cloud dataset containing points and intensity. More... | |
class | LinearLeastSquaresNormalEstimation |
Surface normal estimation on dense data using a least-squares estimation based on a first-order Taylor approximation. More... | |
class | MomentInvariantsEstimation |
MomentInvariantsEstimation estimates the 3 moment invariants (j1, j2, j3) at each 3D point. More... | |
class | MomentOfInertiaEstimation |
Implements the method for extracting features based on moment of inertia. More... | |
class | MultiscaleFeaturePersistence |
Generic class for extracting the persistent features from an input point cloud It can be given any Feature estimator instance and will compute the features of the input over a multiscale representation of the cloud and output the unique ones over those scales. More... | |
class | Narf |
NARF (Normal Aligned Radial Features) is a point feature descriptor type for 3D data. More... | |
class | NarfDescriptor |
Computes NARF feature descriptors for points in a range image See B. More... | |
class | NormalEstimation |
NormalEstimation estimates local surface properties (surface normals and curvatures)at each 3D point. More... | |
class | NormalEstimationOMP |
NormalEstimationOMP estimates local surface properties at each 3D point, such as surface normals and curvatures, in parallel, using the OpenMP standard. More... | |
class | NormalBasedSignatureEstimation |
Normal-based feature signature estimation class. More... | |
class | OrganizedEdgeBase |
OrganizedEdgeBase, OrganizedEdgeFromRGB, OrganizedEdgeFromNormals, and OrganizedEdgeFromRGBNormals find 3D edges from an organized point cloud data. More... | |
class | OrganizedEdgeFromRGB |
class | OrganizedEdgeFromNormals |
class | OrganizedEdgeFromRGBNormals |
class | OURCVFHEstimation |
OURCVFHEstimation estimates the Oriented, Unique and Repetable Clustered Viewpoint Feature Histogram (CVFH) descriptor for a given point cloud dataset given XYZ data and normals, as presented in: More... | |
class | PFHEstimation |
PFHEstimation estimates the Point Feature Histogram (PFH) descriptor for a given point cloud dataset containing points and normals. More... | |
class | PFHRGBEstimation |
Similar to the Point Feature Histogram descriptor, but also takes color into account. More... | |
class | PPFEstimation |
Class that calculates the "surflet" features for each pair in the given pointcloud. More... | |
class | PPFRGBEstimation |
class | PPFRGBRegionEstimation |
class | PrincipalCurvaturesEstimation |
PrincipalCurvaturesEstimation estimates the directions (eigenvectors) and magnitudes (eigenvalues) of principal surface curvatures for a given point cloud dataset containing points and normals. More... | |
class | RangeImageBorderExtractor |
Extract obstacle borders from range images, meaning positions where there is a transition from foreground to background. More... | |
class | RIFTEstimation |
RIFTEstimation estimates the Rotation Invariant Feature Transform descriptors for a given point cloud dataset containing points and intensity. More... | |
class | ROPSEstimation |
This class implements the method for extracting RoPS features presented in the article "Rotational Projection Statistics for 3D Local Surface Description and Object Recognition" by Yulan Guo, Ferdous Sohel, Mohammed Bennamoun, Min Lu and Jianwei Wan. More... | |
class | RSDEstimation |
RSDEstimation estimates the Radius-based Surface Descriptor (minimal and maximal radius of the local surface's curves) for a given point cloud dataset containing points and normals. More... | |
class | SHOTEstimationBase |
SHOTEstimation estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset containing points and normals. More... | |
class | SHOTEstimation |
SHOTEstimation estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset containing points and normals. More... | |
class | SHOTColorEstimation |
SHOTColorEstimation estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset containing points, normals and colors. More... | |
class | SHOTLocalReferenceFrameEstimation |
SHOTLocalReferenceFrameEstimation estimates the Local Reference Frame used in the calculation of the (SHOT) descriptor. More... | |
class | SHOTLocalReferenceFrameEstimationOMP |
SHOTLocalReferenceFrameEstimation estimates the Local Reference Frame used in the calculation of the (SHOT) descriptor. More... | |
class | SHOTEstimationOMP |
SHOTEstimationOMP estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset containing points and normals, in parallel, using the OpenMP standard. More... | |
class | SHOTColorEstimationOMP |
SHOTColorEstimationOMP estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset containing points, normals and colors, in parallel, using the OpenMP standard. More... | |
class | SpinImageEstimation |
Estimates spin-image descriptors in the given input points. More... | |
class | StatisticalMultiscaleInterestRegionExtraction |
Class for extracting interest regions from unstructured point clouds, based on a multi scale statistical approach. More... | |
class | UniqueShapeContext |
UniqueShapeContext implements the Unique Shape Context Descriptor described here: More... | |
class | VFHEstimation |
VFHEstimation estimates the Viewpoint Feature Histogram (VFH) descriptor for a given point cloud dataset containing points and normals. More... | |
struct | xNdCopyEigenPointFunctor |
Helper functor structure for copying data between an Eigen::VectorXf and a PointT. More... | |
struct | xNdCopyPointEigenFunctor |
Helper functor structure for copying data between an Eigen::VectorXf and a PointT. More... | |
class | ApproximateVoxelGrid |
ApproximateVoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More... | |
class | BilateralFilter |
A bilateral filter implementation for point cloud data. More... | |
class | BoxClipper3D |
Implementation of a box clipper in 3D. Actually it allows affine transformations, thus any parallelepiped in general pose. The affine transformation is used to transform the point before clipping it using a cube centered at origin and with an extend of -1 to +1 in each dimension. More... | |
class | Clipper3D |
Base class for 3D clipper objects. More... | |
class | PointDataAtOffset |
A datatype that enables type-correct comparisons. More... | |
class | ComparisonBase |
The (abstract) base class for the comparison object. More... | |
class | FieldComparison |
The field-based specialization of the comparison object. More... | |
class | PackedRGBComparison |
A packed rgb specialization of the comparison object. More... | |
class | PackedHSIComparison |
A packed HSI specialization of the comparison object. More... | |
class | TfQuadraticXYZComparison |
A comparison whether the (x,y,z) components of a given point satisfy (p'Ap + 2v'p + c [OP] 0). More... | |
class | ConditionBase |
Base condition class. More... | |
class | ConditionAnd |
AND condition. More... | |
class | ConditionOr |
OR condition. More... | |
class | ConditionalRemoval |
ConditionalRemoval filters data that satisfies certain conditions. More... | |
class | CovarianceSampling |
Point Cloud sampling based on the 6D covariances. More... | |
class | CropBox |
CropBox is a filter that allows the user to filter all the data inside of a given box. More... | |
class | CropBox< pcl::PCLPointCloud2 > |
CropBox is a filter that allows the user to filter all the data inside of a given box. More... | |
class | CropHull |
Filter points that lie inside or outside a 3D closed surface or 2D closed polygon, as generated by the ConvexHull or ConcaveHull classes. More... | |
class | ExtractIndices |
ExtractIndices extracts a set of indices from a point cloud. More... | |
class | ExtractIndices< pcl::PCLPointCloud2 > |
ExtractIndices extracts a set of indices from a point cloud. More... | |
class | FarthestPointSampling |
FarthestPointSampling applies farthest point sampling using euclidean distance, starting with a random point, utilizing a naive method. More... | |
class | FastBilateralFilter |
Implementation of a fast bilateral filter for smoothing depth information in organized point clouds Based on the following paper: More... | |
class | FastBilateralFilterOMP |
Implementation of a fast bilateral filter for smoothing depth information in organized point clouds Based on the following paper: More... | |
class | Filter |
Filter represents the base filter class. More... | |
class | Filter< pcl::PCLPointCloud2 > |
Filter represents the base filter class. More... | |
class | FilterIndices |
FilterIndices represents the base class for filters that are about binary point removal. More... | |
class | FilterIndices< pcl::PCLPointCloud2 > |
FilterIndices represents the base class for filters that are about binary point removal. More... | |
class | FrustumCulling |
FrustumCulling filters points inside a frustum given by pose and field of view of the camera. More... | |
class | GridMinimum |
GridMinimum assembles a local 2D grid over a given PointCloud, and downsamples the data. More... | |
class | LocalMaximum |
LocalMaximum downsamples the cloud, by eliminating points that are locally maximal. More... | |
class | MedianFilter |
Implementation of the median filter. More... | |
class | ModelOutlierRemoval |
ModelOutlierRemoval filters points in a cloud based on the distance between model and point. More... | |
class | NormalRefinement |
Normal vector refinement class More... | |
class | NormalSpaceSampling |
NormalSpaceSampling samples the input point cloud in the space of normal directions computed at every point. More... | |
class | PassThrough |
PassThrough passes points in a cloud based on constraints for one particular field of the point type. More... | |
class | PassThrough< pcl::PCLPointCloud2 > |
PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints. More... | |
class | PlaneClipper3D |
Implementation of a plane clipper in 3D. More... | |
class | ProjectInliers |
ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a separate PointCloud. More... | |
class | ProjectInliers< pcl::PCLPointCloud2 > |
ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a separate PointCloud. More... | |
class | RadiusOutlierRemoval |
RadiusOutlierRemoval filters points in a cloud based on the number of neighbors they have. More... | |
class | RadiusOutlierRemoval< pcl::PCLPointCloud2 > |
RadiusOutlierRemoval is a simple filter that removes outliers if the number of neighbors in a certain search radius is smaller than a given K. More... | |
class | RandomSample |
RandomSample applies a random sampling with uniform probability. More... | |
class | RandomSample< pcl::PCLPointCloud2 > |
RandomSample applies a random sampling with uniform probability. More... | |
class | SamplingSurfaceNormal |
SamplingSurfaceNormal divides the input space into grids until each grid contains a maximum of N points, and samples points randomly within each grid. More... | |
class | ShadowPoints |
ShadowPoints removes the ghost points appearing on edge discontinuties More... | |
class | StatisticalOutlierRemoval |
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. More... | |
class | StatisticalOutlierRemoval< pcl::PCLPointCloud2 > |
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. More... | |
class | UniformSampling |
UniformSampling assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More... | |
class | VoxelGrid |
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More... | |
class | VoxelGrid< pcl::PCLPointCloud2 > |
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More... | |
class | VoxelGridCovariance |
A searchable voxel structure containing the mean and covariance of the data. More... | |
class | VoxelGridLabel |
class | VoxelGridOcclusionEstimation |
VoxelGrid to estimate occluded space in the scene. More... | |
class | LineIterator |
Organized Index Iterator for iterating over the "pixels" for a given line using the Bresenham algorithm. More... | |
class | OrganizedIndexIterator |
base class for iterators on 2-dimensional maps like images/organized clouds etc. More... | |
class | PlanarPolygon |
PlanarPolygon represents a planar (2D) polygon, potentially in a 3D space. More... | |
class | TSDFVolume |
class | AdaptiveRangeCoder |
AdaptiveRangeCoder compression class More... | |
class | StaticRangeCoder |
StaticRangeCoder compression class More... | |
class | ASCIIReader |
Ascii Point Cloud Reader. More... | |
class | DavidSDKGrabber |
Grabber for davidSDK structured light compliant devices. More... | |
class | DepthSenseGrabber |
Grabber for DepthSense devices (e.g. More... | |
class | DinastGrabber |
Grabber for DINAST devices (i.e., IPA-1002, IPA-1110, IPA-2001) More... | |
class | EnsensoGrabber |
Grabber for IDS-Imaging Ensenso's devices. More... | |
class | FileGrabber |
FileGrabber provides a container-style interface for grabbers which operate on fixed-size input. More... | |
class | FileReader |
Point Cloud Data (FILE) file format reader interface. More... | |
class | FileWriter |
Point Cloud Data (FILE) file format writer. More... | |
class | Grabber |
Grabber interface for PCL 1.x device drivers. More... | |
class | HDLGrabber |
Grabber for the Velodyne High-Definition-Laser (HDL) More... | |
class | IFSReader |
Indexed Face set (IFS) file format reader. More... | |
class | IFSWriter |
Point Cloud Data (IFS) file format writer. More... | |
class | ImageGrabberBase |
Base class for Image file grabber. More... | |
class | ImageGrabber |
class | SynchronizedQueue |
class | MTLReader |
class | OBJReader |
class | ONIGrabber |
A simple ONI grabber. More... | |
class | OpenNIGrabber |
Grabber for OpenNI devices (i.e., Primesense PSDK, Microsoft Kinect, Asus XTion Pro/Live) More... | |
class | PCDGrabberBase |
Base class for PCD file grabber. More... | |
class | PCDGrabber |
class | PCDReader |
Point Cloud Data (PCD) file format reader. More... | |
class | PCDWriter |
Point Cloud Data (PCD) file format writer. More... | |
class | PLYReader |
Point Cloud Data (PLY) file format reader. More... | |
class | PLYWriter |
Point Cloud Data (PLY) file format writer. More... | |
class | RealSense2Grabber |
Grabber for Intel Realsense 2 SDK devices (D400 series) More... | |
class | RealSenseGrabber |
class | RobotEyeGrabber |
Grabber for the Ocular Robotics RobotEye sensor. More... | |
class | TimGrabber |
class | VLPGrabber |
Grabber for the Velodyne LiDAR (VLP), based on the Velodyne High Definition Laser (HDL) More... | |
class | KdTree |
KdTree represents the base spatial locator class for kd-tree implementations. More... | |
class | KdTreeFLANN |
KdTreeFLANN is a generic type of 3D spatial locator using kD-tree structures. More... | |
class | AgastKeypoint2DBase |
Detects 2D AGAST corner points. More... | |
class | AgastKeypoint2D |
Detects 2D AGAST corner points. More... | |
class | AgastKeypoint2D< pcl::PointXYZ, pcl::PointUV > |
Detects 2D AGAST corner points. More... | |
class | BriskKeypoint2D |
Detects BRISK interest points based on the original code and paper reference by. More... | |
class | HarrisKeypoint2D |
HarrisKeypoint2D detects Harris corners family points. More... | |
class | HarrisKeypoint3D |
HarrisKeypoint3D uses the idea of 2D Harris keypoints, but instead of using image gradients, it uses surface normals. More... | |
class | HarrisKeypoint6D |
Keypoint detector for detecting corners in 3D (XYZ), 2D (intensity) AND mixed versions of these. More... | |
class | ISSKeypoint3D |
ISSKeypoint3D detects the Intrinsic Shape Signatures keypoints for a given point cloud. More... | |
class | NarfKeypoint |
NARF (Normal Aligned Radial Feature) keypoints. More... | |
struct | SIFTKeypointFieldSelector |
struct | SIFTKeypointFieldSelector< PointNormal > |
struct | SIFTKeypointFieldSelector< PointXYZRGB > |
struct | SIFTKeypointFieldSelector< PointXYZRGBA > |
class | SIFTKeypoint |
SIFTKeypoint detects the Scale Invariant Feature Transform keypoints for a given point cloud dataset containing points and intensity. More... | |
class | SmoothedSurfacesKeypoint |
Based on the paper: Xinju Li and Igor Guskov Multi-scale features for approximate alignment of point-based surfaces Proceedings of the third Eurographics symposium on Geometry processing July 2005, Vienna, Austria. More... | |
class | SUSANKeypoint |
SUSANKeypoint implements a RGB-D extension of the SUSAN detector including normal directions variation in top of intensity variation. More... | |
class | TrajkovicKeypoint2D |
TrajkovicKeypoint2D implements Trajkovic and Hedley corner detector on organized point cloud using intensity information. More... | |
class | TrajkovicKeypoint3D |
TrajkovicKeypoint3D implements Trajkovic and Hedley corner detector on point cloud using geometric information. More... | |
class | BranchEstimator |
Interface for branch estimators. More... | |
class | BinaryTreeThresholdBasedBranchEstimator |
Branch estimator for binary trees where the branch is computed only from the threshold. More... | |
class | TernaryTreeMissingDataBranchEstimator |
Branch estimator for ternary trees where one branch is used for missing data (indicated by flag != 0). More... | |
class | DenseCrf |
class | DecisionForest |
Class representing a decision forest. More... | |
class | DecisionForestEvaluator |
Utility class for evaluating a decision forests. More... | |
class | DecisionForestTrainer |
Trainer for decision trees. More... | |
class | DecisionTree |
Class representing a decision tree. More... | |
class | DecisionTreeTrainerDataProvider |
class | DecisionTreeEvaluator |
Utility class for evaluating a decision tree. More... | |
class | DecisionTreeTrainer |
Trainer for decision trees. More... | |
class | FeatureHandler |
Utility class interface which is used for creating and evaluating features. More... | |
class | Fern |
Class representing a Fern. More... | |
class | FernEvaluator |
Utility class for evaluating a fern. More... | |
class | FernTrainer |
Trainer for a Fern. More... | |
class | Kmeans |
K-means clustering. More... | |
class | MultiChannel2DComparisonFeature |
Feature for comparing two sample points in 2D multi-channel data. More... | |
class | MultiChannel2DComparisonFeatureHandler |
Feature utility class that handles the creation and evaluation of RGBD comparison features. More... | |
class | ScaledMultiChannel2DComparisonFeatureHandler |
Feature utility class that handles the creation and evaluation of RGBD comparison features. More... | |
class | ScaledMultiChannel2DComparisonFeatureHandlerCCodeGenerator |
class | MultiChannel2DData |
Holds two-dimensional multi-channel data. More... | |
class | MultiChannel2DDataSet |
Holds a set of two-dimensional multi-channel data. More... | |
struct | MultipleData2DExampleIndex |
Example index for a set of 2D data blocks. More... | |
class | PairwisePotential |
class | Permutohedral |
Implementation of a high-dimensional gaussian filtering using the permutohedral lattice. More... | |
class | HashTableOLD |
class | PointXY32f |
2D point with float x- and y-coordinates. More... | |
class | PointXY32i |
2D point with integer x- and y-coordinates. More... | |
class | RegressionVarianceNode |
Node for a regression trees which optimizes variance. More... | |
class | RegressionVarianceStatsEstimator |
Statistics estimator for regression trees which optimizes variance. More... | |
class | StatsEstimator |
Class interface for gathering statistics for decision tree learning. More... | |
struct | SVMParam |
The structure stores the parameters for the classificationa nd must be initialized and passed to the training method pcl::SVMTrain. More... | |
struct | SVMModel |
The structure initialize a model created by the SVM (Support Vector Machines) classifier (pcl::SVMTrain). More... | |
struct | SVMDataPoint |
The structure initialize a single feature value for the classification using SVM (Support Vector Machines). More... | |
struct | SVMData |
The structure stores the features and the label of a single sample which has to be used for the training or the classification of the SVM (Support Vector Machines). More... | |
class | SVM |
Base class for SVM SVM (Support Vector Machines). More... | |
class | SVMTrain |
SVM (Support Vector Machines) training class for the SVM machine learning. More... | |
class | SVMClassify |
SVM (Support Vector Machines) classification of a dataset. More... | |
class | CorrespondenceGrouping |
Abstract base class for Correspondence Grouping algorithms. More... | |
class | GeometricConsistencyGrouping |
Class implementing a 3D correspondence grouping enforcing geometric consistency among feature correspondences. More... | |
class | Hough3DGrouping |
Class implementing a 3D correspondence grouping algorithm that can deal with multiple instances of a model template found into a given scene. More... | |
class | ColorGradientDOTModality |
class | ColorGradientModality |
Modality based on max-RGB gradients. More... | |
class | ColorModality |
class | CRHAlignment |
CRHAlignment uses two Camera Roll Histograms (CRH) to find the roll rotation that aligns both views. More... | |
struct | DenseQuantizedSingleModTemplate |
struct | DenseQuantizedMultiModTemplate |
class | DistanceMap |
Represents a distance map obtained from a distance transformation. More... | |
class | DOTModality |
struct | DOTMODDetection |
class | DOTMOD |
Template matching using the DOTMOD approach. More... | |
class | RFFaceDetectorTrainer |
class | GreedyVerification |
A greedy hypothesis verification method. More... | |
class | GlobalHypothesesVerification |
A hypothesis verification method proposed in "A Global Hypotheses Verification Method for 3D Object Recognition", A. More... | |
class | PapazovHV |
A hypothesis verification method proposed in "An Efficient RANSAC for 3D Object Recognition in Noisy and Occluded Scenes", C. More... | |
class | HypothesisVerification |
Abstract class for hypotheses verification methods. More... | |
struct | ISMPeak |
This struct is used for storing peak. More... | |
struct | BoundingBoxXYZ |
class | LineRGBD |
High-level class for template matching using the LINEMOD approach based on RGB and Depth data. More... | |
class | EnergyMaps |
Stores a set of energy maps. More... | |
class | LinearizedMaps |
Stores a set of linearized maps. More... | |
struct | LINEMODDetection |
Represents a detection of a template using the LINEMOD approach. More... | |
class | LINEMOD |
Template matching using the LINEMOD approach. More... | |
class | MaskMap |
struct | GradientXY |
A point structure representing Euclidean xyz coordinates, and the intensity value. More... | |
class | QuantizableModality |
Interface for a quantizable modality. More... | |
class | QuantizedMap |
struct | RegionXY |
Defines a region in XY-space. More... | |
struct | QuantizedMultiModFeature |
Feature that defines a position and quantized value in a specific modality. More... | |
struct | SparseQuantizedMultiModTemplate |
A multi-modality template constructed from a set of quantized multi-modality features. More... | |
struct | LINEMOD_OrientationMap |
Map that stores orientations. More... | |
struct | QuantizedNormalLookUpTable |
Look-up-table for fast surface normal quantization. More... | |
class | SurfaceNormalModality |
Modality based on surface normals. More... | |
class | SolverDidntConvergeException |
An exception that is thrown when the non linear solver didn't converge. More... | |
class | NotEnoughPointsException |
An exception that is thrown when the number of correspondents is not equal to the minimum required. More... | |
class | GeneralizedIterativeClosestPoint |
GeneralizedIterativeClosestPoint is an ICP variant that implements the generalized iterative closest point algorithm as described by Alex Segal et al. More... | |
class | GeneralizedIterativeClosestPoint6D |
GeneralizedIterativeClosestPoint6D integrates L*a*b* color space information into the Generalized Iterative Closest Point (GICP) algorithm. More... | |
class | GraphRegistration |
GraphRegistration class is the base class for graph-based registration methods More... | |
class | SampleConsensusInitialAlignment |
SampleConsensusInitialAlignment is an implementation of the initial alignment algorithm described in section IV of "Fast Point Feature Histograms (FPFH)
for 3D Registration," Rusu et al. More... | |
class | IterativeClosestPoint |
IterativeClosestPoint provides a base implementation of the Iterative Closest Point algorithm. More... | |
class | IterativeClosestPointWithNormals |
IterativeClosestPointWithNormals is a special case of IterativeClosestPoint, that uses a transformation estimated based on Point to Plane distances by default. More... | |
class | IterativeClosestPointNonLinear |
IterativeClosestPointNonLinear is an ICP variant that uses Levenberg-Marquardt optimization backend. More... | |
class | JointIterativeClosestPoint |
JointIterativeClosestPoint extends ICP to multiple frames which share the same transform. More... | |
class | NormalDistributionsTransform |
A 3D Normal Distribution Transform registration implementation for point cloud data. More... | |
class | NormalDistributionsTransform2D |
NormalDistributionsTransform2D provides an implementation of the Normal Distributions Transform algorithm for scan matching. More... | |
class | PairwiseGraphRegistration |
PairwiseGraphRegistration class aligns the clouds two by two More... | |
class | PPFHashMapSearch |
class | PPFRegistration |
Class that registers two point clouds based on their sets of PPFSignatures. More... | |
class | PyramidFeatureHistogram |
Class that compares two sets of features by using a multiscale representation of the features inside a pyramid. More... | |
class | Registration |
Registration represents the base registration class for general purpose, ICP-like methods. More... | |
class | SampleConsensusPrerejective |
Pose estimation and alignment class using a prerejective RANSAC routine. More... | |
class | LeastMedianSquares |
LeastMedianSquares represents an implementation of the LMedS (Least Median of Squares) algorithm. More... | |
class | MaximumLikelihoodSampleConsensus |
MaximumLikelihoodSampleConsensus represents an implementation of the MLESAC (Maximum Likelihood Estimator SAmple Consensus) algorithm, as described in: "MLESAC: A new robust estimator with application to
estimating image geometry", P.H.S. More... | |
class | MEstimatorSampleConsensus |
MEstimatorSampleConsensus represents an implementation of the MSAC (M-estimator SAmple Consensus) algorithm, as described in: "MLESAC: A new robust estimator with application to estimating image geometry", P.H.S. More... | |
class | ProgressiveSampleConsensus |
ProgressiveSampleConsensus represents an implementation of the PROSAC (PROgressive SAmple Consensus) algorithm, as described in: "Matching with PROSAC – Progressive Sample Consensus", Chum, O. 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 | RandomizedMEstimatorSampleConsensus |
RandomizedMEstimatorSampleConsensus represents an implementation of the RMSAC (Randomized M-estimator SAmple Consensus) algorithm, which basically adds a Td,d test (see RandomizedRandomSampleConsensus) to an MSAC estimator (see MEstimatorSampleConsensus). More... | |
class | RandomizedRandomSampleConsensus |
RandomizedRandomSampleConsensus represents an implementation of the RRANSAC (Randomized RANdom SAmple Consensus), as described in "Randomized RANSAC with Td,d test", O. More... | |
class | SampleConsensus |
SampleConsensus represents the base class. More... | |
class | SampleConsensusModel |
SampleConsensusModel represents the base model class. More... | |
class | SampleConsensusModelFromNormals |
SampleConsensusModelFromNormals represents the base model class for models that require the use of surface normals for estimation. More... | |
struct | Functor |
Base functor all the models that need non linear optimization must define their own one and implement operator() (const Eigen::VectorXd& x, Eigen::VectorXd& fvec) or operator() (const Eigen::VectorXf& x, Eigen::VectorXf& fvec) depending on the chosen _Scalar. More... | |
class | SampleConsensusModelCircle2D |
SampleConsensusModelCircle2D defines a model for 2D circle segmentation on the X-Y plane. More... | |
class | SampleConsensusModelCircle3D |
SampleConsensusModelCircle3D defines a model for 3D circle segmentation. More... | |
class | SampleConsensusModelCone |
SampleConsensusModelCone defines a model for 3D cone segmentation. More... | |
class | SampleConsensusModelCylinder |
SampleConsensusModelCylinder defines a model for 3D cylinder segmentation. More... | |
class | SampleConsensusModelEllipse3D |
SampleConsensusModelEllipse3D defines a model for 3D ellipse segmentation. More... | |
class | SampleConsensusModelLine |
SampleConsensusModelLine defines a model for 3D line segmentation. More... | |
class | SampleConsensusModelNormalParallelPlane |
SampleConsensusModelNormalParallelPlane defines a model for 3D plane segmentation using additional surface normal constraints. More... | |
class | SampleConsensusModelNormalPlane |
SampleConsensusModelNormalPlane defines a model for 3D plane segmentation using additional surface normal constraints. More... | |
class | SampleConsensusModelNormalSphere |
SampleConsensusModelNormalSphere defines a model for 3D sphere segmentation using additional surface normal constraints. More... | |
class | SampleConsensusModelParallelLine |
SampleConsensusModelParallelLine defines a model for 3D line segmentation using additional angular constraints. More... | |
class | SampleConsensusModelParallelPlane |
SampleConsensusModelParallelPlane defines a model for 3D plane segmentation using additional angular constraints. More... | |
class | SampleConsensusModelPerpendicularPlane |
SampleConsensusModelPerpendicularPlane defines a model for 3D plane segmentation using additional angular constraints. More... | |
class | SampleConsensusModelPlane |
SampleConsensusModelPlane defines a model for 3D plane segmentation. More... | |
class | SampleConsensusModelRegistration |
SampleConsensusModelRegistration defines a model for Point-To-Point registration outlier rejection. More... | |
class | SampleConsensusModelRegistration2D |
SampleConsensusModelRegistration2D defines a model for Point-To-Point registration outlier rejection using distances between 2D pixels. More... | |
class | SampleConsensusModelSphere |
SampleConsensusModelSphere defines a model for 3D sphere segmentation. More... | |
class | SampleConsensusModelStick |
SampleConsensusModelStick defines a model for 3D stick segmentation. More... | |
class | SampleConsensusModelTorus |
SampleConsensusModelTorus defines a model for 3D torus segmentation. More... | |
class | ApproximateProgressiveMorphologicalFilter |
Implements the Progressive Morphological Filter for segmentation of ground points. More... | |
class | Comparator |
Comparator is the base class for comparators that compare two points given some function. More... | |
class | ConditionalEuclideanClustering |
ConditionalEuclideanClustering performs segmentation based on Euclidean distance and a user-defined clustering condition. More... | |
class | CPCSegmentation |
A segmentation algorithm partitioning a supervoxel graph. More... | |
class | CrfNormalSegmentation |
class | CrfSegmentation |
class | EdgeAwarePlaneComparator |
EdgeAwarePlaneComparator is a Comparator that operates on plane coefficients, for use in planar segmentation. More... | |
class | EuclideanClusterComparator |
EuclideanClusterComparator is a comparator used for finding clusters based on euclidean distance. More... | |
class | EuclideanPlaneCoefficientComparator |
EuclideanPlaneCoefficientComparator is a Comparator that operates on plane coefficients, for use in planar segmentation. More... | |
class | EuclideanClusterExtraction |
EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense. More... | |
class | LabeledEuclideanClusterExtraction |
LabeledEuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense, with label info. More... | |
class | ExtractPolygonalPrismData |
ExtractPolygonalPrismData uses a set of point indices that represent a planar model, and together with a given height, generates a 3D polygonal prism. More... | |
class | GrabCut |
Implementation of the GrabCut segmentation in "GrabCut — Interactive Foreground Extraction using Iterated Graph Cuts" by Carsten Rother, Vladimir Kolmogorov and Andrew Blake. More... | |
class | GroundPlaneComparator |
GroundPlaneComparator is a Comparator for detecting smooth surfaces suitable for driving. More... | |
class | LCCPSegmentation |
A simple segmentation algorithm partitioning a supervoxel graph into groups of locally convex connected supervoxels separated by concave borders. More... | |
class | MinCutSegmentation |
This class implements the segmentation algorithm based on minimal cut of the graph. More... | |
class | OrganizedConnectedComponentSegmentation |
OrganizedConnectedComponentSegmentation allows connected components to be found within organized point cloud data, given a comparison function. More... | |
class | OrganizedMultiPlaneSegmentation |
OrganizedMultiPlaneSegmentation finds all planes present in the input cloud, and outputs a vector of plane equations, as well as a vector of point clouds corresponding to the inliers of each detected plane. More... | |
class | PlanarPolygonFusion |
PlanarPolygonFusion takes a list of 2D planar polygons and attempts to reduce them to a minimum set that best represents the scene, based on various given comparators. More... | |
class | PlanarRegion |
PlanarRegion represents a set of points that lie in a plane. More... | |
class | PlaneCoefficientComparator |
PlaneCoefficientComparator is a Comparator that operates on plane coefficients, for use in planar segmentation. More... | |
class | PlaneRefinementComparator |
PlaneRefinementComparator is a Comparator that operates on plane coefficients, for use in planar segmentation. More... | |
class | ProgressiveMorphologicalFilter |
Implements the Progressive Morphological Filter for segmentation of ground points. More... | |
class | Region3D |
Region3D represents summary statistics of a 3D collection of points. More... | |
class | RegionGrowing |
Implements the well known Region Growing algorithm used for segmentation. More... | |
class | RegionGrowingRGB |
Implements the well known Region Growing algorithm used for segmentation based on color of points. More... | |
class | RGBPlaneCoefficientComparator |
RGBPlaneCoefficientComparator is a Comparator that operates on plane coefficients, for use in planar segmentation. More... | |
class | SACSegmentation |
SACSegmentation represents the Nodelet segmentation class for Sample Consensus methods and models, in the sense that it just creates a Nodelet wrapper for generic-purpose SAC-based segmentation. More... | |
class | SACSegmentationFromNormals |
SACSegmentationFromNormals represents the PCL nodelet segmentation class for Sample Consensus methods and models that require the use of surface normals for estimation. More... | |
class | SeededHueSegmentation |
SeededHueSegmentation. More... | |
class | SegmentDifferences |
SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the difference between them for a maximum given distance threshold. More... | |
class | Supervoxel |
Supervoxel container class - stores a cluster extracted using supervoxel clustering. More... | |
class | SupervoxelClustering |
Implements a supervoxel algorithm based on voxel structure, normals, and rgb values. More... | |
class | UnaryClassifier |
class | DigitalElevationMapBuilder |
Build a Digital Elevation Map in the column-disparity space from a disparity map and a color image of the scene. More... | |
class | DisparityMapConverter |
Compute point cloud from the disparity map. More... | |
class | StereoGrabberBase |
Base class for Stereo file grabber. More... | |
class | StereoGrabber |
class | StereoMatching |
Stereo Matching abstract class. More... | |
class | GrayStereoMatching |
Stereo Matching abstract class for Grayscale images. More... | |
class | BlockBasedStereoMatching |
Block based (or fixed window) Stereo Matching class. More... | |
class | AdaptiveCostSOStereoMatching |
Adaptive Cost 2-pass Scanline Optimization Stereo Matching class. More... | |
class | BilateralUpsampling |
Bilateral filtering implementation, based on the following paper: More... | |
class | ConcaveHull |
ConcaveHull (alpha shapes) using libqhull library. More... | |
class | ConvexHull |
ConvexHull using libqhull library. More... | |
class | EarClipping |
The ear clipping triangulation algorithm. More... | |
class | GreedyProjectionTriangulation |
GreedyProjectionTriangulation is an implementation of a greedy triangulation algorithm for 3D points based on local 2D projections. More... | |
class | GridProjection |
Grid projection surface reconstruction method. More... | |
class | MarchingCubes |
The marching cubes surface reconstruction algorithm. More... | |
class | MarchingCubesHoppe |
The marching cubes surface reconstruction algorithm, using a signed distance function based on the distance from tangent planes, proposed by Hoppe et. More... | |
class | MarchingCubesRBF |
The marching cubes surface reconstruction algorithm, using a signed distance function based on radial basis functions. More... | |
struct | MLSResult |
Data structure used to store the results of the MLS fitting. More... | |
class | MovingLeastSquares |
MovingLeastSquares represent an implementation of the MLS (Moving Least Squares) algorithm for data smoothing and improved normal estimation. More... | |
class | OrganizedFastMesh |
Simple triangulation/surface reconstruction for organized point clouds. More... | |
class | Poisson |
The Poisson surface reconstruction algorithm. More... | |
class | CloudSurfaceProcessing |
CloudSurfaceProcessing represents the base class for algorithms that takes a point cloud as input and produces a new output cloud that has been modified towards a better surface representation. More... | |
class | MeshProcessing |
MeshProcessing represents the base class for mesh processing algorithms. More... | |
class | PCLSurfaceBase |
Pure abstract class. More... | |
class | SurfaceReconstruction |
SurfaceReconstruction represents a base surface reconstruction class. More... | |
class | MeshConstruction |
MeshConstruction represents a base surface reconstruction class. More... | |
class | SurfelSmoothing |
class | TextureMapping |
The texture mapping algorithm. More... | |
class | MeshQuadricDecimationVTK |
PCL mesh decimation based on vtkQuadricDecimation from the VTK library. More... | |
class | MeshSmoothingLaplacianVTK |
PCL mesh smoothing based on the vtkSmoothPolyDataFilter algorithm from the VTK library. More... | |
class | MeshSmoothingWindowedSincVTK |
PCL mesh smoothing based on the vtkWindowedSincPolyDataFilter algorithm from the VTK library. More... | |
class | MeshSubdivisionVTK |
PCL mesh smoothing based on the vtkLinearSubdivisionFilter, vtkLoopSubdivisionFilter, vtkButterflySubdivisionFilter depending on the selected MeshSubdivisionVTKFilterType algorithm from the VTK library. More... | |
class | VTKUtils |
class | RegistrationVisualizer |
RegistrationVisualizer represents the base class for rendering the intermediate positions occupied by the source point cloud during it's registration to the target point cloud. More... | |
class | vtkXRenderWindowInteractor |
Functions | |
float | rad2deg (float alpha) |
Convert an angle from radians to degrees. More... | |
float | deg2rad (float alpha) |
Convert an angle from degrees to radians. More... | |
double | rad2deg (double alpha) |
Convert an angle from radians to degrees. More... | |
double | deg2rad (double alpha) |
Convert an angle from degrees to radians. More... | |
float | normAngle (float alpha) |
Normalize an angle to (-PI, PI]. More... | |
template<typename real > | |
std::ostream & | operator<< (std::ostream &os, const BivariatePolynomialT< real > &p) |
template<typename PointT , typename Scalar > | |
unsigned int | compute3DCentroid (ConstCloudIterator< PointT > &cloud_iterator, Eigen::Matrix< Scalar, 4, 1 > ¢roid) |
Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector. More... | |
template<typename PointT > | |
unsigned int | compute3DCentroid (ConstCloudIterator< PointT > &cloud_iterator, Eigen::Vector4f ¢roid) |
template<typename PointT > | |
unsigned int | compute3DCentroid (ConstCloudIterator< PointT > &cloud_iterator, Eigen::Vector4d ¢roid) |
template<typename PointT , typename Scalar > | |
unsigned int | compute3DCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix< Scalar, 4, 1 > ¢roid) |
Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector. More... | |
template<typename PointT > | |
unsigned int | compute3DCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::Vector4f ¢roid) |
template<typename PointT > | |
unsigned int | compute3DCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::Vector4d ¢roid) |
template<typename PointT , typename Scalar > | |
unsigned int | compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix< Scalar, 4, 1 > ¢roid) |
Compute the 3D (X-Y-Z) centroid of a set of points using their indices and return it as a 3D vector. More... | |
template<typename PointT > | |
unsigned int | compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Vector4f ¢roid) |
template<typename PointT > | |
unsigned int | compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Vector4d ¢roid) |
template<typename PointT , typename Scalar > | |
unsigned int | compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix< Scalar, 4, 1 > ¢roid) |
Compute the 3D (X-Y-Z) centroid of a set of points using their indices and return it as a 3D vector. More... | |
template<typename PointT > | |
unsigned int | compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Vector4f ¢roid) |
template<typename PointT > | |
unsigned int | compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Vector4d ¢roid) |
template<typename PointT , typename Scalar > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the 3x3 covariance matrix of a given set of points. More... | |
template<typename PointT > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4f ¢roid, Eigen::Matrix3f &covariance_matrix) |
template<typename PointT > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4d ¢roid, Eigen::Matrix3d &covariance_matrix) |
template<typename PointT , typename Scalar > | |
unsigned int | computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute normalized the 3x3 covariance matrix of a given set of points. More... | |
template<typename PointT > | |
unsigned int | computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4f ¢roid, Eigen::Matrix3f &covariance_matrix) |
template<typename PointT > | |
unsigned int | computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4d ¢roid, Eigen::Matrix3d &covariance_matrix) |
template<typename PointT , typename Scalar > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Indices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the 3x3 covariance matrix of a given set of points using their indices. More... | |
template<typename PointT > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Indices &indices, const Eigen::Vector4f ¢roid, Eigen::Matrix3f &covariance_matrix) |
template<typename PointT > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Indices &indices, const Eigen::Vector4d ¢roid, Eigen::Matrix3d &covariance_matrix) |
template<typename PointT , typename Scalar > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the 3x3 covariance matrix of a given set of points using their indices. More... | |
template<typename PointT > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Vector4f ¢roid, Eigen::Matrix3f &covariance_matrix) |
template<typename PointT > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Vector4d ¢roid, Eigen::Matrix3d &covariance_matrix) |
template<typename PointT , typename Scalar > | |
unsigned int | computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const Indices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the normalized 3x3 covariance matrix of a given set of points using their indices. More... | |
template<typename PointT > | |
unsigned int | computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const Indices &indices, const Eigen::Vector4f ¢roid, Eigen::Matrix3f &covariance_matrix) |
template<typename PointT > | |
unsigned int | computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const Indices &indices, const Eigen::Vector4d ¢roid, Eigen::Matrix3d &covariance_matrix) |
template<typename PointT , typename Scalar > | |
unsigned int | computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the normalized 3x3 covariance matrix of a given set of points using their indices. More... | |
template<typename PointT > | |
unsigned int | computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Vector4f ¢roid, Eigen::Matrix3f &covariance_matrix) |
template<typename PointT > | |
unsigned int | computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Vector4d ¢roid, Eigen::Matrix3d &covariance_matrix) |
template<typename PointT , typename Scalar > | |
unsigned int | computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix, Eigen::Matrix< Scalar, 4, 1 > ¢roid) |
Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. More... | |
template<typename PointT > | |
unsigned int | computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix3f &covariance_matrix, Eigen::Vector4f ¢roid) |
template<typename PointT > | |
unsigned int | computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix3d &covariance_matrix, Eigen::Vector4d ¢roid) |
template<typename PointT , typename Scalar > | |
unsigned int | computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix, Eigen::Matrix< Scalar, 4, 1 > ¢roid) |
Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. More... | |
template<typename PointT > | |
unsigned int | computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix3f &covariance_matrix, Eigen::Vector4f ¢roid) |
template<typename PointT > | |
unsigned int | computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix3d &covariance_matrix, Eigen::Vector4d ¢roid) |
template<typename PointT , typename Scalar > | |
unsigned int | computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix, Eigen::Matrix< Scalar, 4, 1 > ¢roid) |
Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. More... | |
template<typename PointT > | |
unsigned int | computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix3f &covariance_matrix, Eigen::Vector4f ¢roid) |
template<typename PointT > | |
unsigned int | computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix3d &covariance_matrix, Eigen::Vector4d ¢roid) |
template<typename PointT , typename Scalar > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the normalized 3x3 covariance matrix for a already demeaned point cloud. More... | |
template<typename PointT > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix3f &covariance_matrix) |
template<typename PointT > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix3d &covariance_matrix) |
template<typename PointT , typename Scalar > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the normalized 3x3 covariance matrix for a already demeaned point cloud. More... | |
template<typename PointT > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix3f &covariance_matrix) |
template<typename PointT > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix3d &covariance_matrix) |
template<typename PointT , typename Scalar > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the normalized 3x3 covariance matrix for a already demeaned point cloud. More... | |
template<typename PointT > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix3f &covariance_matrix) |
template<typename PointT > | |
unsigned int | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix3d &covariance_matrix) |
template<typename PointT , typename Scalar > | |
unsigned int | computeCentroidAndOBB (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix< Scalar, 3, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 1 > &obb_center, Eigen::Matrix< Scalar, 3, 1 > &obb_dimensions, Eigen::Matrix< Scalar, 3, 3 > &obb_rotational_matrix) |
Compute centroid, OBB (Oriented Bounding Box), PCA axes of a given set of points. More... | |
template<typename PointT , typename Scalar > | |
unsigned int | computeCentroidAndOBB (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix< Scalar, 3, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 1 > &obb_center, Eigen::Matrix< Scalar, 3, 1 > &obb_dimensions, Eigen::Matrix< Scalar, 3, 3 > &obb_rotational_matrix) |
Compute centroid, OBB (Oriented Bounding Box), PCA axes of a given set of points. More... | |
template<typename PointT , typename Scalar > | |
void | demeanPointCloud (ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, pcl::PointCloud< PointT > &cloud_out, int npts=0) |
Subtract a centroid from a point cloud and return the de-meaned representation. More... | |
template<typename PointT > | |
void | demeanPointCloud (ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Vector4f ¢roid, pcl::PointCloud< PointT > &cloud_out, int npts=0) |
template<typename PointT > | |
void | demeanPointCloud (ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Vector4d ¢roid, pcl::PointCloud< PointT > &cloud_out, int npts=0) |
template<typename PointT , typename Scalar > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, pcl::PointCloud< PointT > &cloud_out) |
Subtract a centroid from a point cloud and return the de-meaned representation. More... | |
template<typename PointT > | |
void | demeanPointCloud (ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Vector4f ¢roid, pcl::PointCloud< PointT > &cloud_out) |
template<typename PointT > | |
void | demeanPointCloud (ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Vector4d ¢roid, pcl::PointCloud< PointT > &cloud_out) |
template<typename PointT , typename Scalar > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, pcl::PointCloud< PointT > &cloud_out) |
Subtract a centroid from a point cloud and return the de-meaned representation. More... | |
template<typename PointT > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, const Eigen::Vector4f ¢roid, pcl::PointCloud< PointT > &cloud_out) |
template<typename PointT > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, const Eigen::Vector4d ¢roid, pcl::PointCloud< PointT > &cloud_out) |
template<typename PointT , typename Scalar > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, pcl::PointCloud< PointT > &cloud_out) |
Subtract a centroid from a point cloud and return the de-meaned representation. More... | |
template<typename PointT > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, const Eigen::Vector4f ¢roid, pcl::PointCloud< PointT > &cloud_out) |
template<typename PointT > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, const Eigen::Vector4d ¢roid, pcl::PointCloud< PointT > &cloud_out) |
template<typename PointT , typename Scalar > | |
void | demeanPointCloud (ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > &cloud_out, int npts=0) |
Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix. More... | |
template<typename PointT > | |
void | demeanPointCloud (ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Vector4f ¢roid, Eigen::MatrixXf &cloud_out, int npts=0) |
template<typename PointT > | |
void | demeanPointCloud (ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Vector4d ¢roid, Eigen::MatrixXd &cloud_out, int npts=0) |
template<typename PointT , typename Scalar > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > &cloud_out) |
Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix. More... | |
template<typename PointT > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Eigen::Vector4f ¢roid, Eigen::MatrixXf &cloud_out) |
template<typename PointT > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Eigen::Vector4d ¢roid, Eigen::MatrixXd &cloud_out) |
template<typename PointT , typename Scalar > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > &cloud_out) |
Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix. More... | |
template<typename PointT > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, const Eigen::Vector4f ¢roid, Eigen::MatrixXf &cloud_out) |
template<typename PointT > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, const Eigen::Vector4d ¢roid, Eigen::MatrixXd &cloud_out) |
template<typename PointT , typename Scalar > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > &cloud_out) |
Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix. More... | |
template<typename PointT > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, const Eigen::Vector4f ¢roid, Eigen::MatrixXf &cloud_out) |
template<typename PointT > | |
void | demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, const Eigen::Vector4d ¢roid, Eigen::MatrixXd &cloud_out) |
template<typename PointT , typename Scalar > | |
void | computeNDCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > ¢roid) |
General, all purpose nD centroid estimation for a set of points using their indices. More... | |
template<typename PointT > | |
void | computeNDCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::VectorXf ¢roid) |
template<typename PointT > | |
void | computeNDCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::VectorXd ¢roid) |
template<typename PointT , typename Scalar > | |
void | computeNDCentroid (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > ¢roid) |
General, all purpose nD centroid estimation for a set of points using their indices. More... | |
template<typename PointT > | |
void | computeNDCentroid (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::VectorXf ¢roid) |
template<typename PointT > | |
void | computeNDCentroid (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::VectorXd ¢roid) |
template<typename PointT , typename Scalar > | |
void | computeNDCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > ¢roid) |
General, all purpose nD centroid estimation for a set of points using their indices. More... | |
template<typename PointT > | |
void | computeNDCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::VectorXf ¢roid) |
template<typename PointT > | |
void | computeNDCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::VectorXd ¢roid) |
template<typename PointInT , typename PointOutT > | |
std::size_t | computeCentroid (const pcl::PointCloud< PointInT > &cloud, PointOutT ¢roid) |
Compute the centroid of a set of points and return it as a point. More... | |
template<typename PointInT , typename PointOutT > | |
std::size_t | computeCentroid (const pcl::PointCloud< PointInT > &cloud, const Indices &indices, PointOutT ¢roid) |
Compute the centroid of a set of points and return it as a point. More... | |
PCL_EXPORTS RGB | getRandomColor (double min=0.2, double max=2.8) |
template<typename T , std::uint8_t bits = 8> | |
std::array< T, 1<< bits > | RGB2sRGB_LUT () noexcept |
Returns a Look-Up Table useful in converting RGB to sRGB. More... | |
template<typename T , std::size_t discretizations = 4000> | |
const std::array< T, discretizations > & | XYZ2LAB_LUT () noexcept |
Returns a Look-Up Table useful in converting scaled CIE XYZ into CIE L*a*b*. More... | |
double | getAngle3D (const Eigen::Vector4f &v1, const Eigen::Vector4f &v2, const bool in_degree=false) |
Compute the smallest angle between two 3D vectors in radians (default) or degree. More... | |
double | getAngle3D (const Eigen::Vector3f &v1, const Eigen::Vector3f &v2, const bool in_degree=false) |
Compute the smallest angle between two 3D vectors in radians (default) or degree. More... | |
void | getMeanStd (const std::vector< float > &values, double &mean, double &stddev) |
Compute both the mean and the standard deviation of an array of values. More... | |
template<typename PointT > | |
void | getPointsInBox (const pcl::PointCloud< PointT > &cloud, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, Indices &indices) |
Get a set of points residing in a box given its bounds. More... | |
template<typename PointT > | |
void | getMaxDistance (const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt) |
Get the point at maximum distance from a given point and a given pointcloud. More... | |
template<typename PointT > | |
void | getMaxDistance (const pcl::PointCloud< PointT > &cloud, const Indices &indices, const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt) |
Get the point at maximum distance from a given point and a given pointcloud. More... | |
template<typename PointT > | |
void | getMinMax3D (const pcl::PointCloud< PointT > &cloud, PointT &min_pt, PointT &max_pt) |
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud. More... | |
template<typename PointT > | |
void | getMinMax3D (const pcl::PointCloud< PointT > &cloud, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt) |
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud. More... | |
template<typename PointT > | |
void | getMinMax3D (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt) |
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud. More... | |
template<typename PointT > | |
void | getMinMax3D (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt) |
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud. More... | |
template<typename PointT > | |
double | getCircumcircleRadius (const PointT &pa, const PointT &pb, const PointT &pc) |
Compute the radius of a circumscribed circle for a triangle formed of three points pa, pb, and pc. More... | |
template<typename PointT > | |
void | getMinMax (const PointT &histogram, int len, float &min_p, float &max_p) |
Get the minimum and maximum values on a point histogram. More... | |
template<typename PointT > | |
float | calculatePolygonArea (const pcl::PointCloud< PointT > &polygon) |
Calculate the area of a polygon given a point cloud that defines the polygon. More... | |
PCL_EXPORTS void | getMinMax (const pcl::PCLPointCloud2 &cloud, int idx, const std::string &field_name, float &min_p, float &max_p) |
Get the minimum and maximum values on a point histogram. More... | |
PCL_EXPORTS void | getMeanStdDev (const std::vector< float > &values, double &mean, double &stddev) |
Compute both the mean and the standard deviation of an array of values. More... | |
template<typename IteratorT , typename Functor > | |
auto | computeMedian (IteratorT begin, IteratorT end, Functor f) noexcept -> std::result_of_t< Functor(decltype(*begin))> |
Compute the median of a list of values (fast). More... | |
template<typename IteratorT > | |
auto | computeMedian (IteratorT begin, IteratorT end) noexcept -> typename std::iterator_traits< IteratorT >::value_type |
Compute the median of a list of values (fast). More... | |
template<typename PointInT , typename PointOutT > | |
void | copyPoint (const PointInT &point_in, PointOutT &point_out) |
Copy the fields of a source point into a target point. More... | |
PCL_EXPORTS void | lineToLineSegment (const Eigen::VectorXf &line_a, const Eigen::VectorXf &line_b, Eigen::Vector4f &pt1_seg, Eigen::Vector4f &pt2_seg) |
Get the shortest 3D segment between two 3D lines. More... | |
double | sqrPointToLineDistance (const Eigen::Vector4f &pt, const Eigen::Vector4f &line_pt, const Eigen::Vector4f &line_dir) |
Get the square distance from a point to a line (represented by a point and a direction) More... | |
double | sqrPointToLineDistance (const Eigen::Vector4f &pt, const Eigen::Vector4f &line_pt, const Eigen::Vector4f &line_dir, const double sqr_length) |
Get the square distance from a point to a line (represented by a point and a direction) More... | |
template<typename PointT > | |
double | getMaxSegment (const pcl::PointCloud< PointT > &cloud, PointT &pmin, PointT &pmax) |
Obtain the maximum segment in a given set of points, and return the minimum and maximum points. More... | |
template<typename PointT > | |
double | getMaxSegment (const pcl::PointCloud< PointT > &cloud, const Indices &indices, PointT &pmin, PointT &pmax) |
Obtain the maximum segment in a given set of points, and return the minimum and maximum points. More... | |
template<typename PointType1 , typename PointType2 > | |
float | squaredEuclideanDistance (const PointType1 &p1, const PointType2 &p2) |
Calculate the squared euclidean distance between the two given points. More... | |
template<> | |
float | squaredEuclideanDistance (const PointXY &p1, const PointXY &p2) |
Calculate the squared euclidean distance between the two given points. More... | |
template<typename PointType1 , typename PointType2 > | |
float | euclideanDistance (const PointType1 &p1, const PointType2 &p2) |
Calculate the euclidean distance between the two given points. More... | |
template<typename Scalar , typename Roots > | |
void | computeRoots2 (const Scalar &b, const Scalar &c, Roots &roots) |
Compute the roots of a quadratic polynom x^2 + b*x + c = 0. More... | |
template<typename Matrix , typename Roots > | |
void | computeRoots (const Matrix &m, Roots &roots) |
computes the roots of the characteristic polynomial of the input matrix m, which are the eigenvalues More... | |
template<typename Matrix , typename Vector > | |
void | eigen22 (const Matrix &mat, typename Matrix::Scalar &eigenvalue, Vector &eigenvector) |
determine the smallest eigenvalue and its corresponding eigenvector More... | |
template<typename Matrix , typename Vector > | |
void | eigen22 (const Matrix &mat, Matrix &eigenvectors, Vector &eigenvalues) |
determine the smallest eigenvalue and its corresponding eigenvector More... | |
template<typename Matrix , typename Vector > | |
void | computeCorrespondingEigenVector (const Matrix &mat, const typename Matrix::Scalar &eigenvalue, Vector &eigenvector) |
determines the corresponding eigenvector to the given eigenvalue of the symmetric positive semi definite input matrix More... | |
template<typename Matrix , typename Vector > | |
void | eigen33 (const Matrix &mat, typename Matrix::Scalar &eigenvalue, Vector &eigenvector) |
determines the eigenvector and eigenvalue of the smallest eigenvalue of the symmetric positive semi definite input matrix More... | |
template<typename Matrix , typename Vector > | |
void | eigen33 (const Matrix &mat, Vector &evals) |
determines the eigenvalues of the symmetric positive semi definite input matrix More... | |
template<typename Matrix , typename Vector > | |
void | eigen33 (const Matrix &mat, Matrix &evecs, Vector &evals) |
determines the eigenvalues and corresponding eigenvectors of the symmetric positive semi definite input matrix More... | |
template<typename Matrix > | |
Matrix::Scalar | invert2x2 (const Matrix &matrix, Matrix &inverse) |
Calculate the inverse of a 2x2 matrix. More... | |
template<typename Matrix > | |
Matrix::Scalar | invert3x3SymMatrix (const Matrix &matrix, Matrix &inverse) |
Calculate the inverse of a 3x3 symmetric matrix. More... | |
template<typename Matrix > | |
Matrix::Scalar | invert3x3Matrix (const Matrix &matrix, Matrix &inverse) |
Calculate the inverse of a general 3x3 matrix. More... | |
template<typename Matrix > | |
Matrix::Scalar | determinant3x3Matrix (const Matrix &matrix) |
Calculate the determinant of a 3x3 matrix. More... | |
void | getTransFromUnitVectorsZY (const Eigen::Vector3f &z_axis, const Eigen::Vector3f &y_direction, Eigen::Affine3f &transformation) |
Get the unique 3D rotation that will rotate z_axis into (0,0,1) and y_direction into a vector with x=0 (or into (0,1,0) should y_direction be orthogonal to z_axis) More... | |
Eigen::Affine3f | getTransFromUnitVectorsZY (const Eigen::Vector3f &z_axis, const Eigen::Vector3f &y_direction) |
Get the unique 3D rotation that will rotate z_axis into (0,0,1) and y_direction into a vector with x=0 (or into (0,1,0) should y_direction be orthogonal to z_axis) More... | |
void | getTransFromUnitVectorsXY (const Eigen::Vector3f &x_axis, const Eigen::Vector3f &y_direction, Eigen::Affine3f &transformation) |
Get the unique 3D rotation that will rotate x_axis into (1,0,0) and y_direction into a vector with z=0 (or into (0,1,0) should y_direction be orthogonal to z_axis) More... | |
Eigen::Affine3f | getTransFromUnitVectorsXY (const Eigen::Vector3f &x_axis, const Eigen::Vector3f &y_direction) |
Get the unique 3D rotation that will rotate x_axis into (1,0,0) and y_direction into a vector with z=0 (or into (0,1,0) should y_direction be orthogonal to z_axis) More... | |
void | getTransformationFromTwoUnitVectors (const Eigen::Vector3f &y_direction, const Eigen::Vector3f &z_axis, Eigen::Affine3f &transformation) |
Get the unique 3D rotation that will rotate z_axis into (0,0,1) and y_direction into a vector with x=0 (or into (0,1,0) should y_direction be orthogonal to z_axis) More... | |
Eigen::Affine3f | getTransformationFromTwoUnitVectors (const Eigen::Vector3f &y_direction, const Eigen::Vector3f &z_axis) |
Get the unique 3D rotation that will rotate z_axis into (0,0,1) and y_direction into a vector with x=0 (or into (0,1,0) should y_direction be orthogonal to z_axis) More... | |
void | getTransformationFromTwoUnitVectorsAndOrigin (const Eigen::Vector3f &y_direction, const Eigen::Vector3f &z_axis, const Eigen::Vector3f &origin, Eigen::Affine3f &transformation) |
Get the transformation that will translate origin to (0,0,0) and rotate z_axis into (0,0,1) and y_direction into a vector with x=0 (or into (0,1,0) should y_direction be orthogonal to z_axis) More... | |
template<typename Scalar > | |
void | getEulerAngles (const Eigen::Transform< Scalar, 3, Eigen::Affine > &t, Scalar &roll, Scalar &pitch, Scalar &yaw) |
Extract the Euler angles (intrinsic rotations, ZYX-convention) from the given transformation. More... | |
template<typename Scalar > | |
void | getTranslationAndEulerAngles (const Eigen::Transform< Scalar, 3, Eigen::Affine > &t, Scalar &x, Scalar &y, Scalar &z, Scalar &roll, Scalar &pitch, Scalar &yaw) |
Extract x,y,z and the Euler angles (intrinsic rotations, ZYX-convention) from the given transformation. More... | |
template<typename Scalar > | |
void | getTransformation (Scalar x, Scalar y, Scalar z, Scalar roll, Scalar pitch, Scalar yaw, Eigen::Transform< Scalar, 3, Eigen::Affine > &t) |
Create a transformation from the given translation and Euler angles (intrinsic rotations, ZYX-convention) More... | |
void | getTransformation (float x, float y, float z, float roll, float pitch, float yaw, Eigen::Affine3f &t) |
void | getTransformation (double x, double y, double z, double roll, double pitch, double yaw, Eigen::Affine3d &t) |
Eigen::Affine3f | getTransformation (float x, float y, float z, float roll, float pitch, float yaw) |
Create a transformation from the given translation and Euler angles (intrinsic rotations, ZYX-convention) More... | |
template<typename Derived > | |
void | saveBinary (const Eigen::MatrixBase< Derived > &matrix, std::ostream &file) |
Write a matrix to an output stream. More... | |
template<typename Derived > | |
void | loadBinary (Eigen::MatrixBase< Derived > const &matrix, std::istream &file) |
Read a matrix from an input stream. More... | |
template<typename Derived , typename OtherDerived > | |
Eigen::internal::umeyama_transform_matrix_type< Derived, OtherDerived >::type | umeyama (const Eigen::MatrixBase< Derived > &src, const Eigen::MatrixBase< OtherDerived > &dst, bool with_scaling=false) |
Returns the transformation between two point sets. More... | |
template<typename Scalar > | |
void | transformPoint (const Eigen::Matrix< Scalar, 3, 1 > &point_in, Eigen::Matrix< Scalar, 3, 1 > &point_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transformation) |
Transform a point using an affine matrix. More... | |
template<typename Scalar > | |
void | transformVector (const Eigen::Matrix< Scalar, 3, 1 > &vector_in, Eigen::Matrix< Scalar, 3, 1 > &vector_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transformation) |
Transform a vector using an affine matrix. More... | |
template<typename Scalar > | |
bool | transformLine (const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &line_in, Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &line_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transformation) |
Transform a line using an affine matrix. More... | |
template<typename Scalar > | |
void | transformPlane (const Eigen::Matrix< Scalar, 4, 1 > &plane_in, Eigen::Matrix< Scalar, 4, 1 > &plane_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transformation) |
Transform plane vectors using an affine matrix. More... | |
template<typename Scalar > | |
void | transformPlane (const pcl::ModelCoefficients::ConstPtr plane_in, pcl::ModelCoefficients::Ptr plane_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transformation) |
Transform plane vectors using an affine matrix. More... | |
template<typename Scalar > | |
bool | checkCoordinateSystem (const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &line_x, const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &line_y, const Scalar norm_limit=1e-3, const Scalar dot_limit=1e-3) |
Check coordinate system integrity. More... | |
template<typename Scalar > | |
bool | checkCoordinateSystem (const Eigen::Matrix< Scalar, 3, 1 > &origin, const Eigen::Matrix< Scalar, 3, 1 > &x_direction, const Eigen::Matrix< Scalar, 3, 1 > &y_direction, const Scalar norm_limit=1e-3, const Scalar dot_limit=1e-3) |
Check coordinate system integrity. More... | |
template<typename Scalar > | |
bool | transformBetween2CoordinateSystems (const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > from_line_x, const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > from_line_y, const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > to_line_x, const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > to_line_y, Eigen::Transform< Scalar, 3, Eigen::Affine > &transformation) |
Compute the transformation between two coordinate systems. More... | |
void | getAllPcdFilesInDirectory (const std::string &directory, std::vector< std::string > &file_names) |
Find all *.pcd files in the directory and return them sorted. More... | |
std::string | getFilenameWithoutPath (const std::string &input) |
Remove the path from the given string and return only the filename (the remaining string after the last '/') More... | |
std::string | getFilenameWithoutExtension (const std::string &input) |
Remove the extension from the given string and return only the filename (everything before the last '. More... | |
std::string | getFileExtension (const std::string &input) |
Get the file extension from the given string (the remaining string after the last '. More... | |
template<typename PointT , typename Scalar > | |
unsigned | computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the 3x3 covariance matrix of a given set of points. More... | |
bool | lineWithLineIntersection (const Eigen::VectorXf &line_a, const Eigen::VectorXf &line_b, Eigen::Vector4f &point, double sqr_eps=1e-4) |
Get the intersection of a two 3D lines in space as a 3D point. More... | |
bool | lineWithLineIntersection (const pcl::ModelCoefficients &line_a, const pcl::ModelCoefficients &line_b, Eigen::Vector4f &point, double sqr_eps=1e-4) |
Get the intersection of a two 3D lines in space as a 3D point. More... | |
template<typename Scalar > | |
bool | planeWithPlaneIntersection (const Eigen::Matrix< Scalar, 4, 1 > &plane_a, const Eigen::Matrix< Scalar, 4, 1 > &plane_b, Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &line, double angular_tolerance=0.1) |
Determine the line of intersection of two non-parallel planes using lagrange multipliers. More... | |
template<typename Scalar > | |
bool | threePlanesIntersection (const Eigen::Matrix< Scalar, 4, 1 > &plane_a, const Eigen::Matrix< Scalar, 4, 1 > &plane_b, const Eigen::Matrix< Scalar, 4, 1 > &plane_c, Eigen::Matrix< Scalar, 3, 1 > &intersection_point, double determinant_tolerance=1e-6) |
Determine the point of intersection of three non-parallel planes by solving the equations. More... | |
template<typename PointT > | |
int | getFieldIndex (const pcl::PointCloud< PointT > &, const std::string &field_name, std::vector< pcl::PCLPointField > &fields) |
template<typename PointT > | |
int | getFieldIndex (const std::string &field_name, std::vector< pcl::PCLPointField > &fields) |
Get the index of a specified field (i.e., dimension/channel) More... | |
template<typename PointT > | |
int | getFieldIndex (const std::string &field_name, const std::vector< pcl::PCLPointField > &fields) |
Get the index of a specified field (i.e., dimension/channel) More... | |
template<typename PointT > | |
void | getFields (const pcl::PointCloud< PointT > &, std::vector< pcl::PCLPointField > &fields) |
template<typename PointT > | |
void | getFields (std::vector< pcl::PCLPointField > &fields) |
template<typename PointT > | |
std::vector< pcl::PCLPointField > | getFields () |
Get the list of available fields (i.e., dimension/channel) More... | |
template<typename PointT > | |
std::string | getFieldsList (const pcl::PointCloud< PointT > &cloud) |
Get the list of all fields available in a given cloud. More... | |
template<typename PointInT , typename PointOutT > | |
void | copyPointCloud (const pcl::PointCloud< PointInT > &cloud_in, pcl::PointCloud< PointOutT > &cloud_out) |
Copy all the fields from a given point cloud into a new point cloud. More... | |
template<typename PointT , typename IndicesVectorAllocator > | |
void | copyPointCloud (const pcl::PointCloud< PointT > &cloud_in, const IndicesAllocator< IndicesVectorAllocator > &indices, pcl::PointCloud< PointT > &cloud_out) |
Extract the indices of a given point cloud as a new point cloud. More... | |
template<typename PointInT , typename PointOutT , typename IndicesVectorAllocator > | |
void | copyPointCloud (const pcl::PointCloud< PointInT > &cloud_in, const IndicesAllocator< IndicesVectorAllocator > &indices, pcl::PointCloud< PointOutT > &cloud_out) |
Extract the indices of a given point cloud as a new point cloud. More... | |
template<typename PointT > | |
void | copyPointCloud (const pcl::PointCloud< PointT > &cloud_in, const PointIndices &indices, pcl::PointCloud< PointT > &cloud_out) |
Extract the indices of a given point cloud as a new point cloud. More... | |
template<typename PointInT , typename PointOutT > | |
void | copyPointCloud (const pcl::PointCloud< PointInT > &cloud_in, const PointIndices &indices, pcl::PointCloud< PointOutT > &cloud_out) |
Extract the indices of a given point cloud as a new point cloud. More... | |
template<typename PointT > | |
void | copyPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< pcl::PointIndices > &indices, pcl::PointCloud< PointT > &cloud_out) |
Extract the indices of a given point cloud as a new point cloud. More... | |
template<typename PointInT , typename PointOutT > | |
void | copyPointCloud (const pcl::PointCloud< PointInT > &cloud_in, const std::vector< pcl::PointIndices > &indices, pcl::PointCloud< PointOutT > &cloud_out) |
Extract the indices of a given point cloud as a new point cloud. More... | |
template<typename PointIn1T , typename PointIn2T , typename PointOutT > | |
void | concatenateFields (const pcl::PointCloud< PointIn1T > &cloud1_in, const pcl::PointCloud< PointIn2T > &cloud2_in, pcl::PointCloud< PointOutT > &cloud_out) |
Concatenate two datasets representing different fields. More... | |
template<typename PointT > | |
void | copyPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, int top, int bottom, int left, int right, pcl::InterpolationType border_type, const PointT &value) |
Copy a point cloud inside a larger one interpolating borders. More... | |
template<typename FloatVectorT > | |
float | selectNorm (FloatVectorT A, FloatVectorT B, int dim, NormType norm_type) |
Method that calculates any norm type available, based on the norm_type variable. More... | |
template<typename FloatVectorT > | |
float | L1_Norm (FloatVectorT A, FloatVectorT B, int dim) |
Compute the L1 norm of the vector between two points. More... | |
template<typename FloatVectorT > | |
float | L2_Norm_SQR (FloatVectorT A, FloatVectorT B, int dim) |
Compute the squared L2 norm of the vector between two points. More... | |
template<typename FloatVectorT > | |
float | L2_Norm (FloatVectorT A, FloatVectorT B, int dim) |
Compute the L2 norm of the vector between two points. More... | |
template<typename FloatVectorT > | |
float | Linf_Norm (FloatVectorT A, FloatVectorT B, int dim) |
Compute the L-infinity norm of the vector between two points. More... | |
template<typename FloatVectorT > | |
float | JM_Norm (FloatVectorT A, FloatVectorT B, int dim) |
Compute the JM norm of the vector between two points. More... | |
template<typename FloatVectorT > | |
float | B_Norm (FloatVectorT A, FloatVectorT B, int dim) |
Compute the B norm of the vector between two points. More... | |
template<typename FloatVectorT > | |
float | Sublinear_Norm (FloatVectorT A, FloatVectorT B, int dim) |
Compute the sublinear norm of the vector between two points. More... | |
template<typename FloatVectorT > | |
float | CS_Norm (FloatVectorT A, FloatVectorT B, int dim) |
Compute the CS norm of the vector between two points. More... | |
template<typename FloatVectorT > | |
float | Div_Norm (FloatVectorT A, FloatVectorT B, int dim) |
Compute the div norm of the vector between two points. More... | |
template<typename FloatVectorT > | |
float | PF_Norm (FloatVectorT A, FloatVectorT B, int dim, float P1, float P2) |
Compute the PF norm of the vector between two points. More... | |
template<typename FloatVectorT > | |
float | K_Norm (FloatVectorT A, FloatVectorT B, int dim, float P1, float P2) |
Compute the K norm of the vector between two points. More... | |
template<typename FloatVectorT > | |
float | KL_Norm (FloatVectorT A, FloatVectorT B, int dim) |
Compute the KL between two discrete probability density functions. More... | |
template<typename FloatVectorT > | |
float | HIK_Norm (FloatVectorT A, FloatVectorT B, int dim) |
Compute the HIK norm of the vector between two points. More... | |
template<typename PointT > | |
double | estimateProjectionMatrix (typename pcl::PointCloud< PointT >::ConstPtr cloud, Eigen::Matrix< float, 3, 4, Eigen::RowMajor > &projection_matrix, const Indices &indices={}) |
Estimates the projection matrix P = K * (R|-R*t) from organized point clouds, with K = [[fx, s, cx], [0, fy, cy], [0, 0, 1]] R = rotation matrix and t = translation vector More... | |
template<typename PointT , typename Scalar > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields=true) |
Apply a rigid transform defined by a 4x4 matrix. More... | |
template<typename PointT , typename Scalar > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields=true) |
Apply a rigid transform defined by a 4x4 matrix. More... | |
void | transformPointCloud (const pcl::PointCloud< pcl::PointXY > &cloud_in, pcl::PointCloud< pcl::PointXY > &cloud_out, const Eigen::Affine2f &transform, bool copy_all_fields=true) |
Apply an affine transform on a pointcloud having points of type PointXY. More... | |
template<typename PointT , typename Scalar > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields=true) |
Transform a point cloud and rotate its normals using an Eigen transform. More... | |
template<typename PointT , typename Scalar > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields=true) |
Transform a point cloud and rotate its normals using an Eigen transform. More... | |
template<typename PointT , typename Scalar > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 3, 1 > &offset, const Eigen::Quaternion< Scalar > &rotation, bool copy_all_fields=true) |
Apply a rigid transform defined by a 3D offset and a quaternion. More... | |
template<typename PointT , typename Scalar > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 3, 1 > &offset, const Eigen::Quaternion< Scalar > &rotation, bool copy_all_fields=true) |
Transform a point cloud and rotate its normals using an Eigen transform. More... | |
template<typename PointT , typename Scalar > | |
PointT | transformPoint (const PointT &point, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transform) |
Transform a point with members x,y,z. More... | |
template<typename PointT , typename Scalar > | |
PointT | transformPointWithNormal (const PointT &point, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transform) |
Transform a point with members x,y,z,normal_x,normal_y,normal_z. More... | |
template<typename PointT , typename Scalar > | |
double | getPrincipalTransformation (const pcl::PointCloud< PointT > &cloud, Eigen::Transform< Scalar, 3, Eigen::Affine > &transform) |
Calculates the principal (PCA-based) alignment of the point cloud. More... | |
bool | planeWithPlaneIntersection (const Eigen::Vector4f &plane_a, const Eigen::Vector4f &plane_b, Eigen::VectorXf &line, double angular_tolerance=0.1) |
bool | planeWithPlaneIntersection (const Eigen::Vector4d &plane_a, const Eigen::Vector4d &plane_b, Eigen::VectorXd &line, double angular_tolerance=0.1) |
bool | threePlanesIntersection (const Eigen::Vector4f &plane_a, const Eigen::Vector4f &plane_b, const Eigen::Vector4f &plane_c, Eigen::Vector3f &intersection_point, double determinant_tolerance=1e-6) |
bool | threePlanesIntersection (const Eigen::Vector4d &plane_a, const Eigen::Vector4d &plane_b, const Eigen::Vector4d &plane_c, Eigen::Vector3d &intersection_point, double determinant_tolerance=1e-6) |
int | getFieldIndex (const pcl::PCLPointCloud2 &cloud, const std::string &field_name) |
Get the index of a specified field (i.e., dimension/channel) More... | |
std::string | getFieldsList (const pcl::PCLPointCloud2 &cloud) |
Get the available point cloud fields as a space separated string. More... | |
int | getFieldSize (const int datatype) |
Obtains the size of a specific field data type in bytes. More... | |
PCL_EXPORTS void | getFieldsSizes (const std::vector< pcl::PCLPointField > &fields, std::vector< int > &field_sizes) |
Obtain a vector with the sizes of all valid fields (e.g., not "_") More... | |
int | getFieldType (const int size, char type) |
Obtains the type of the PCLPointField from a specific size and type. More... | |
char | getFieldType (const int type) |
Obtains the type of the PCLPointField from a specific PCLPointField as a char. More... | |
PCL_EXPORTS int | interpolatePointIndex (int p, int length, InterpolationType type) |
template<typename PointT > | |
bool | concatenate (const pcl::PointCloud< PointT > &cloud1, const pcl::PointCloud< PointT > &cloud2, pcl::PointCloud< PointT > &cloud_out) |
Concatenate two pcl::PointCloud<PointT> More... | |
bool | concatenate (const pcl::PCLPointCloud2 &cloud1, const pcl::PCLPointCloud2 &cloud2, pcl::PCLPointCloud2 &cloud_out) |
Concatenate two pcl::PCLPointCloud2. More... | |
bool | concatenate (const pcl::PolygonMesh &mesh1, const pcl::PolygonMesh &mesh2, pcl::PolygonMesh &mesh_out) |
Concatenate two pcl::PolygonMesh. More... | |
PCL_EXPORTS void | copyPointCloud (const pcl::PCLPointCloud2 &cloud_in, const Indices &indices, pcl::PCLPointCloud2 &cloud_out) |
Extract the indices of a given point cloud as a new point cloud. More... | |
PCL_EXPORTS void | copyPointCloud (const pcl::PCLPointCloud2 &cloud_in, const IndicesAllocator< Eigen::aligned_allocator< index_t > > &indices, pcl::PCLPointCloud2 &cloud_out) |
Extract the indices of a given point cloud as a new point cloud. More... | |
PCL_EXPORTS void | copyPointCloud (const pcl::PCLPointCloud2 &cloud_in, pcl::PCLPointCloud2 &cloud_out) |
Copy fields and point cloud data from cloud_in to cloud_out. More... | |
template<typename Point1T , typename Point2T > | |
constexpr bool | isSamePointType () noexcept |
Check if two given point types are the same or not. More... | |
PCL_EXPORTS bool | concatenateFields (const pcl::PCLPointCloud2 &cloud1_in, const pcl::PCLPointCloud2 &cloud2_in, pcl::PCLPointCloud2 &cloud_out) |
Concatenate two datasets representing different fields. More... | |
PCL_EXPORTS bool | getPointCloudAsEigen (const pcl::PCLPointCloud2 &in, Eigen::MatrixXf &out) |
Copy the XYZ dimensions of a pcl::PCLPointCloud2 into Eigen format. More... | |
PCL_EXPORTS bool | getEigenAsPointCloud (Eigen::MatrixXf &in, pcl::PCLPointCloud2 &out) |
Copy the XYZ dimensions from an Eigen MatrixXf into a pcl::PCLPointCloud2 message. More... | |
template<typename PointT > | |
bool | isFinite (const PointT &pt) |
Tests if the 3D components of a point are all finite param[in] pt point to be tested return true if finite, false otherwise. More... | |
template<> | |
bool | isFinite< pcl::Axis > (const pcl::Axis &) |
template<> | |
bool | isFinite< pcl::BRISKSignature512 > (const pcl::BRISKSignature512 &) |
template<> | |
bool | isFinite< pcl::BorderDescription > (const pcl::BorderDescription &) |
template<> | |
bool | isFinite< pcl::Boundary > (const pcl::Boundary &) |
template<> | |
bool | isFinite< pcl::CPPFSignature > (const pcl::CPPFSignature &) |
template<> | |
bool | isFinite< pcl::ESFSignature640 > (const pcl::ESFSignature640 &) |
template<> | |
bool | isFinite< pcl::FPFHSignature33 > (const pcl::FPFHSignature33 &) |
template<> | |
bool | isFinite< pcl::GASDSignature512 > (const pcl::GASDSignature512 &) |
template<> | |
bool | isFinite< pcl::GASDSignature984 > (const pcl::GASDSignature984 &) |
template<> | |
bool | isFinite< pcl::GASDSignature7992 > (const pcl::GASDSignature7992 &) |
template<> | |
bool | isFinite< pcl::GRSDSignature21 > (const pcl::GRSDSignature21 &) |
template<> | |
bool | isFinite< pcl::Intensity > (const pcl::Intensity &) |
template<> | |
bool | isFinite< pcl::IntensityGradient > (const pcl::IntensityGradient &) |
template<> | |
bool | isFinite< pcl::Label > (const pcl::Label &) |
template<> | |
bool | isFinite< pcl::MomentInvariants > (const pcl::MomentInvariants &) |
template<> | |
bool | isFinite< pcl::NormalBasedSignature12 > (const pcl::NormalBasedSignature12 &) |
template<> | |
bool | isFinite< pcl::PFHRGBSignature250 > (const pcl::PFHRGBSignature250 &) |
template<> | |
bool | isFinite< pcl::PFHSignature125 > (const pcl::PFHSignature125 &) |
template<> | |
bool | isFinite< pcl::PPFRGBSignature > (const pcl::PPFRGBSignature &) |
template<> | |
bool | isFinite< pcl::PPFSignature > (const pcl::PPFSignature &pt) |
template<> | |
bool | isFinite< pcl::PrincipalCurvatures > (const pcl::PrincipalCurvatures &) |
template<> | |
bool | isFinite< pcl::PrincipalRadiiRSD > (const pcl::PrincipalRadiiRSD &) |
template<> | |
bool | isFinite< pcl::RGB > (const pcl::RGB &) |
template<> | |
bool | isFinite< pcl::ReferenceFrame > (const pcl::ReferenceFrame &) |
template<> | |
bool | isFinite< pcl::SHOT1344 > (const pcl::SHOT1344 &) |
template<> | |
bool | isFinite< pcl::SHOT352 > (const pcl::SHOT352 &) |
template<> | |
bool | isFinite< pcl::ShapeContext1980 > (const pcl::ShapeContext1980 &) |
template<> | |
bool | isFinite< pcl::UniqueShapeContext1960 > (const pcl::UniqueShapeContext1960 &) |
template<> | |
bool | isFinite< pcl::VFHSignature308 > (const pcl::VFHSignature308 &) |
template<> | |
bool | isFinite< pcl::PointXY > (const pcl::PointXY &p) |
template<> | |
bool | isFinite< pcl::Normal > (const pcl::Normal &n) |
template<typename PointT , traits::HasNoXY< PointT > = true> | |
constexpr bool | isXYFinite (const PointT &) noexcept |
template<typename PointT , traits::HasNoXYZ< PointT > = true> | |
constexpr bool | isXYZFinite (const PointT &) noexcept |
template<typename PointT , traits::HasNoNormal< PointT > = true> | |
constexpr bool | isNormalFinite (const PointT &) noexcept |
template<typename PointT , traits::HasXY< PointT > = true> | |
bool | isXYFinite (const PointT &pt) noexcept |
template<typename PointT , traits::HasXYZ< PointT > = true> | |
bool | isXYZFinite (const PointT &pt) noexcept |
template<typename PointT , traits::HasNormal< PointT > = true> | |
bool | isNormalFinite (const PointT &pt) noexcept |
PCL_EXPORTS void | getCameraMatrixFromProjectionMatrix (const Eigen::Matrix< float, 3, 4, Eigen::RowMajor > &projection_matrix, Eigen::Matrix3f &camera_matrix) |
Determines the camera matrix from the given projection matrix. More... | |
double | getTime () |
template<typename PointT , typename Scalar > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transform, bool copy_all_fields=true) |
Apply an affine transform defined by an Eigen Transform. More... | |
template<typename PointT > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Affine3f &transform, bool copy_all_fields=true) |
template<typename PointT , typename Scalar > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transform, bool copy_all_fields=true) |
Apply an affine transform defined by an Eigen Transform. More... | |
template<typename PointT > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Affine3f &transform, bool copy_all_fields=true) |
template<typename PointT , typename Scalar > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transform, bool copy_all_fields=true) |
Apply an affine transform defined by an Eigen Transform. More... | |
template<typename PointT > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Affine3f &transform, bool copy_all_fields=true) |
template<typename PointT , typename Scalar > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transform, bool copy_all_fields=true) |
Transform a point cloud and rotate its normals using an Eigen transform. More... | |
template<typename PointT > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Affine3f &transform, bool copy_all_fields=true) |
template<typename PointT , typename Scalar > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transform, bool copy_all_fields=true) |
Transform a point cloud and rotate its normals using an Eigen transform. More... | |
template<typename PointT > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Affine3f &transform, bool copy_all_fields=true) |
template<typename PointT , typename Scalar > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transform, bool copy_all_fields=true) |
Transform a point cloud and rotate its normals using an Eigen transform. More... | |
template<typename PointT > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Affine3f &transform, bool copy_all_fields=true) |
template<typename PointT > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform, bool copy_all_fields=true) |
template<typename PointT > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform, bool copy_all_fields=true) |
template<typename PointT , typename Scalar > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields=true) |
Apply a rigid transform defined by a 4x4 matrix. More... | |
template<typename PointT > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform, bool copy_all_fields=true) |
template<typename PointT > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform, bool copy_all_fields=true) |
template<typename PointT > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform, bool copy_all_fields=true) |
template<typename PointT , typename Scalar > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields=true) |
Transform a point cloud and rotate its normals using an Eigen transform. More... | |
template<typename PointT > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix4f &transform, bool copy_all_fields=true) |
template<typename PointT > | |
void | transformPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Vector3f &offset, const Eigen::Quaternionf &rotation, bool copy_all_fields=true) |
template<typename PointT > | |
void | transformPointCloudWithNormals (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Vector3f &offset, const Eigen::Quaternionf &rotation, bool copy_all_fields=true) |
template<typename PointT > | |
PointT | transformPoint (const PointT &point, const Eigen::Affine3f &transform) |
template<typename PointT > | |
PointT | transformPointWithNormal (const PointT &point, const Eigen::Affine3f &transform) |
template<typename PointT > | |
double | getPrincipalTransformation (const pcl::PointCloud< PointT > &cloud, Eigen::Affine3f &transform) |
template<typename PointT > | |
void | createMapping (const std::vector< pcl::PCLPointField > &msg_fields, MsgFieldMap &field_map) |
template<typename PointT > | |
void | fromPCLPointCloud2 (const pcl::PCLPointCloud2 &msg, pcl::PointCloud< PointT > &cloud, const MsgFieldMap &field_map, const std::uint8_t *msg_data) |
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map. More... | |
template<typename PointT > | |
void | fromPCLPointCloud2 (const pcl::PCLPointCloud2 &msg, pcl::PointCloud< PointT > &cloud, const MsgFieldMap &field_map) |
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map. More... | |
template<typename PointT > | |
void | fromPCLPointCloud2 (const pcl::PCLPointCloud2 &msg, pcl::PointCloud< PointT > &cloud) |
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object. More... | |
template<typename PointT > | |
void | toPCLPointCloud2 (const pcl::PointCloud< PointT > &cloud, pcl::PCLPointCloud2 &msg, bool padding) |
Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob. More... | |
template<typename PointT > | |
void | toPCLPointCloud2 (const pcl::PointCloud< PointT > &cloud, pcl::PCLPointCloud2 &msg) |
Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob. More... | |
template<typename CloudT > | |
void | toPCLPointCloud2 (const CloudT &cloud, pcl::PCLImage &msg) |
Copy the RGB fields of a PointCloud into pcl::PCLImage format. More... | |
void | toPCLPointCloud2 (const pcl::PCLPointCloud2 &cloud, pcl::PCLImage &msg) |
Copy the RGB fields of a PCLPointCloud2 msg into pcl::PCLImage format. More... | |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const Correspondence &c) |
overloaded << operator More... | |
void | getRejectedQueryIndices (const pcl::Correspondences &correspondences_before, const pcl::Correspondences &correspondences_after, Indices &indices, bool presorting_required=true) |
Get the query points of correspondences that are present in one correspondence vector but not in the other, e.g., to compare correspondences before and after rejection. More... | |
bool | isBetterCorrespondence (const Correspondence &pc1, const Correspondence &pc2) |
Comparator to enable us to sort a vector of PointCorrespondences according to their scores using std::sort (begin(), end(), isBetterCorrespondence);. More... | |
template<typename Sequence , typename F > | |
void | for_each_type (F f) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointXYZ &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const RGB &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const Intensity &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const Intensity8u &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const Intensity32u &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointXYZI &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointXYZL &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const Label &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointXYZRGBA &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointXYZRGB &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointXYZRGBL &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointXYZLAB &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointXYZHSV &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointXY &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointUV &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const InterestPoint &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const Normal &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const Axis &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointNormal &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointXYZRGBNormal &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointXYZINormal &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointXYZLNormal &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointWithRange &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointWithViewpoint &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const MomentInvariants &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PrincipalRadiiRSD &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const Boundary &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PrincipalCurvatures &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PFHSignature125 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PFHRGBSignature250 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PPFSignature &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const CPPFSignature &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PPFRGBSignature &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const NormalBasedSignature12 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const ShapeContext1980 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const UniqueShapeContext1960 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const SHOT352 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const SHOT1344 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const ReferenceFrame &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const FPFHSignature33 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const VFHSignature308 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const GRSDSignature21 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const BRISKSignature512 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const ESFSignature640 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const GASDSignature512 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const GASDSignature984 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const GASDSignature7992 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const GFPFHSignature16 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const Narf36 &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const BorderDescription &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const IntensityGradient &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointWithScale &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointSurfel &p) |
PCL_EXPORTS std::ostream & | operator<< (std::ostream &os, const PointDEM &p) |
template<int N> | |
std::ostream & | operator<< (std::ostream &os, const Histogram< N > &p) |
template<typename T , typename ... Args> | |
shared_ptr< T > | make_shared (Args &&... args) |
Returns a pcl::shared_ptr compliant with type T's allocation policy. More... | |
std::ostream & | operator<< (std::ostream &s, const ::pcl::ModelCoefficients &v) |
void * | aligned_malloc (std::size_t size) |
void | aligned_free (void *ptr) |
std::ostream & | operator<< (std::ostream &out, const PCLHeader &h) |
bool | operator== (const PCLHeader &lhs, const PCLHeader &rhs) |
std::ostream & | operator<< (std::ostream &s, const ::pcl::PCLImage &v) |
std::ostream & | operator<< (std::ostream &s, const ::pcl::PCLPointCloud2 &v) |
std::ostream & | operator<< (std::ostream &s, const ::pcl::PCLPointField &v) |
template<typename PointT > | |
std::ostream & | operator<< (std::ostream &s, const pcl::PointCloud< PointT > &p) |
void | PointXYZRGBtoXYZI (const PointXYZRGB &in, PointXYZI &out) |
Convert a XYZRGB point type to a XYZI. More... | |
void | PointRGBtoI (const RGB &in, Intensity &out) |
Convert a RGB point type to a I. More... | |
void | PointRGBtoI (const RGB &in, Intensity8u &out) |
Convert a RGB point type to a I. More... | |
void | PointRGBtoI (const RGB &in, Intensity32u &out) |
Convert a RGB point type to a I. More... | |
void | PointXYZRGBtoXYZHSV (const PointXYZRGB &in, PointXYZHSV &out) |
Convert a XYZRGB point type to a XYZHSV. More... | |
template<typename PointT , traits::HasColor< PointT > = true> | |
void | PointXYZRGBtoXYZLAB (const PointT &in, PointXYZLAB &out) |
Convert a XYZRGB-based point type to a XYZLAB. More... | |
void | PointXYZRGBAtoXYZHSV (const PointXYZRGBA &in, PointXYZHSV &out) |
Convert a XYZRGBA point type to a XYZHSV. More... | |
void | PointXYZHSVtoXYZRGB (const PointXYZHSV &in, PointXYZRGB &out) |
void | PointCloudRGBtoI (const PointCloud< RGB > &in, PointCloud< Intensity > &out) |
Convert a RGB point cloud to an Intensity. More... | |
void | PointCloudRGBtoI (const PointCloud< RGB > &in, PointCloud< Intensity8u > &out) |
Convert a RGB point cloud to an Intensity. More... | |
void | PointCloudRGBtoI (const PointCloud< RGB > &in, PointCloud< Intensity32u > &out) |
Convert a RGB point cloud to an Intensity. More... | |
void | PointCloudXYZRGBtoXYZHSV (const PointCloud< PointXYZRGB > &in, PointCloud< PointXYZHSV > &out) |
Convert a XYZRGB point cloud to a XYZHSV. More... | |
void | PointCloudXYZHSVtoXYZRGB (const PointCloud< PointXYZHSV > &in, PointCloud< PointXYZRGB > &out) |
Convert a XYZHSV point cloud to a XYZRGB. More... | |
void | PointCloudXYZRGBAtoXYZHSV (const PointCloud< PointXYZRGBA > &in, PointCloud< PointXYZHSV > &out) |
Convert a XYZRGB point cloud to a XYZHSV. More... | |
void | PointCloudXYZRGBtoXYZI (const PointCloud< PointXYZRGB > &in, PointCloud< PointXYZI > &out) |
Convert a XYZRGB point cloud to a XYZI. More... | |
void | PointCloudDepthAndRGBtoXYZRGBA (const PointCloud< Intensity > &depth, const PointCloud< RGB > &image, const float &focal, PointCloud< PointXYZRGBA > &out) |
Convert registered Depth image and RGB image to PointCloudXYZRGBA. More... | |
std::ostream & | operator<< (std::ostream &s, const ::pcl::PointIndices &v) |
std::ostream & | operator<< (std::ostream &s, const ::pcl::PolygonMesh &v) |
std::ostream & | operator<< (std::ostream &os, const RangeImage &r) |
/ingroup range_image More... | |
template<typename PointT , typename ValT > | |
void | setFieldValue (PointT &pt, std::size_t field_offset, const ValT &value) |
Set the value at a specified field in a point. More... | |
template<typename PointT , typename ValT > | |
void | getFieldValue (const PointT &pt, std::size_t field_offset, ValT &value) |
Get the value at a specified field in a point. More... | |
std::ostream & | operator<< (std::ostream &s, const ::pcl::Vertices &v) |
PCL_EXPORTS bool | computeCPPFPairFeature (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, const Eigen::Vector4i &c1, const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, const Eigen::Vector4i &c2, float &f1, float &f2, float &f3, float &f4, float &f5, float &f6, float &f7, float &f8, float &f9, float &f10) |
void | solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix, const Eigen::Vector4f &point, Eigen::Vector4f &plane_parameters, float &curvature) |
Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squares plane normal and surface curvature. More... | |
void | solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix, float &nx, float &ny, float &nz, float &curvature) |
Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squares plane normal and surface curvature. More... | |
std::ostream & | operator<< (std::ostream &os, const RangeImageBorderExtractor::Parameters &p) |
template<typename PointT > | |
bool | computePointNormal (const pcl::PointCloud< PointT > &cloud, Eigen::Vector4f &plane_parameters, float &curvature) |
Compute the Least-Squares plane fit for a given set of points, and return the estimated plane parameters together with the surface curvature. More... | |
template<typename PointT > | |
bool | computePointNormal (const pcl::PointCloud< PointT > &cloud, const pcl::Indices &indices, Eigen::Vector4f &plane_parameters, float &curvature) |
Compute the Least-Squares plane fit for a given set of points, using their indices, and return the estimated plane parameters together with the surface curvature. More... | |
template<typename PointT , typename Scalar > | |
void | flipNormalTowardsViewpoint (const PointT &point, float vp_x, float vp_y, float vp_z, Eigen::Matrix< Scalar, 4, 1 > &normal) |
Flip (in place) the estimated normal of a point towards a given viewpoint. More... | |
template<typename PointT , typename Scalar > | |
void | flipNormalTowardsViewpoint (const PointT &point, float vp_x, float vp_y, float vp_z, Eigen::Matrix< Scalar, 3, 1 > &normal) |
Flip (in place) the estimated normal of a point towards a given viewpoint. More... | |
template<typename PointT > | |
void | flipNormalTowardsViewpoint (const PointT &point, float vp_x, float vp_y, float vp_z, float &nx, float &ny, float &nz) |
Flip (in place) the estimated normal of a point towards a given viewpoint. More... | |
template<typename PointNT > | |
bool | flipNormalTowardsNormalsMean (pcl::PointCloud< PointNT > const &normal_cloud, pcl::Indices const &normal_indices, Eigen::Vector3f &normal) |
Flip (in place) normal to get the same sign of the mean of the normals specified by normal_indices. More... | |
PCL_EXPORTS bool | computePairFeatures (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, float &f1, float &f2, float &f3, float &f4) |
Compute the 4-tuple representation containing the three angles and one distance between two points represented by Cartesian coordinates and normals. More... | |
PCL_EXPORTS bool | computeRGBPairFeatures (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, const Eigen::Vector4i &colors1, const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, const Eigen::Vector4i &colors2, float &f1, float &f2, float &f3, float &f4, float &f5, float &f6, float &f7) |
PCL_EXPORTS bool | computePPFPairFeature (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, float &f1, float &f2, float &f3, float &f4) |
template<int N> | |
void | getFeaturePointCloud (const std::vector< Eigen::MatrixXf, Eigen::aligned_allocator< Eigen::MatrixXf > > &histograms2D, PointCloud< Histogram< N > > &histogramsPC) |
Transform a list of 2D matrices into a point cloud containing the values in a vector (Histogram<N>). More... | |
template<typename PointInT , typename PointNT , typename PointOutT > | |
Eigen::MatrixXf | computeRSD (const pcl::PointCloud< PointInT > &surface, const pcl::PointCloud< PointNT > &normals, const pcl::Indices &indices, double max_dist, int nr_subdiv, double plane_radius, PointOutT &radii, bool compute_histogram=false) |
Estimate the Radius-based Surface Descriptor (RSD) for a given point based on its spatial neighborhood of 3D points with normals. More... | |
template<typename PointNT , typename PointOutT > | |
Eigen::MatrixXf | computeRSD (const pcl::PointCloud< PointNT > &normals, const pcl::Indices &indices, const std::vector< float > &sqr_dists, double max_dist, int nr_subdiv, double plane_radius, PointOutT &radii, bool compute_histogram=false) |
Estimate the Radius-based Surface Descriptor (RSD) for a given point based on its spatial neighborhood of 3D points with normals. More... | |
template<typename PointT > | |
void | removeNaNFromPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, Indices &index) |
Removes points with x, y, or z equal to NaN. More... | |
template<typename PointT > | |
void | removeNaNNormalsFromPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, Indices &index) |
Removes points that have their normals invalid (i.e., equal to NaN) More... | |
template<typename PointT > | |
void | removeNaNFromPointCloud (const pcl::PointCloud< PointT > &cloud_in, Indices &index) |
Removes points with x, y, or z equal to NaN (dry run). More... | |
template<typename PointT > | |
void | applyMorphologicalOperator (const typename pcl::PointCloud< PointT >::ConstPtr &cloud_in, float resolution, const int morphological_operator, pcl::PointCloud< PointT > &cloud_out) |
Apply morphological operator to the z dimension of the input point cloud. More... | |
template<typename PointT > | |
PCL_EXPORTS void | applyMorphologicalOperator (const typename pcl::PointCloud< PointT >::ConstPtr &cloud_in, float resolution, const int morphological_operator, pcl::PointCloud< PointT > &cloud_out) |
Apply morphological operator to the z dimension of the input point cloud. More... | |
template<typename NormalT > | |
std::vector< float > | assignNormalWeights (const PointCloud< NormalT > &cloud, index_t index, const Indices &k_indices, const std::vector< float > &k_sqr_distances) |
Assign weights of nearby normals used for refinement. More... | |
template<typename NormalT > | |
bool | refineNormal (const PointCloud< NormalT > &cloud, int index, const Indices &k_indices, const std::vector< float > &k_sqr_distances, NormalT &point) |
Refine an indexed point based on its neighbors, this function only writes to the normal_* fields. More... | |
PCL_EXPORTS void | getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt) |
Obtain the maximum and minimum points in 3D from a given point cloud. More... | |
PCL_EXPORTS void | getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const Indices &indices, int x_idx, int y_idx, int z_idx, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt) |
Obtain the maximum and minimum points in 3D from a given point cloud. More... | |
PCL_EXPORTS void | getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, const std::string &distance_field_name, float min_distance, float max_distance, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative=false) |
Obtain the maximum and minimum points in 3D from a given point cloud. More... | |
PCL_EXPORTS void | getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const Indices &indices, int x_idx, int y_idx, int z_idx, const std::string &distance_field_name, float min_distance, float max_distance, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative=false) |
Obtain the maximum and minimum points in 3D from a given point cloud. More... | |
Eigen::MatrixXi | getHalfNeighborCellIndices () |
Get the relative cell indices of the "upper half" 13 neighbors. More... | |
Eigen::MatrixXi | getAllNeighborCellIndices () |
Get the relative cell indices of all the 26 neighbors. More... | |
template<typename PointT > | |
void | getMinMax3D (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const std::string &distance_field_name, float min_distance, float max_distance, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative=false) |
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud, without considering points outside of a distance threshold from the laser origin. More... | |
template<typename PointT > | |
void | getMinMax3D (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const Indices &indices, const std::string &distance_field_name, float min_distance, float max_distance, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative=false) |
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud, without considering points outside of a distance threshold from the laser origin. More... | |
template<typename PointT > | |
void | approximatePolygon (const PlanarPolygon< PointT > &polygon, PlanarPolygon< PointT > &approx_polygon, float threshold, bool refine=false, bool closed=true) |
see approximatePolygon2D More... | |
template<typename PointT > | |
void | approximatePolygon2D (const typename PointCloud< PointT >::VectorType &polygon, typename PointCloud< PointT >::VectorType &approx_polygon, float threshold, bool refine=false, bool closed=true) |
returns an approximate polygon to given 2D contour. More... | |
template<typename Type > | |
std::enable_if_t< std::is_floating_point< Type >::value > | copyValueString (const pcl::PCLPointCloud2 &cloud, const pcl::index_t point_index, const int point_size, const unsigned int field_idx, const unsigned int fields_count, std::ostream &stream) |
inserts a value of type Type (uchar, char, uint, int, float, double, ...) into a stringstream. More... | |
template<typename Type > | |
std::enable_if_t< std::is_integral< Type >::value > | copyValueString (const pcl::PCLPointCloud2 &cloud, const pcl::index_t point_index, const int point_size, const unsigned int field_idx, const unsigned int fields_count, std::ostream &stream) |
template<> | |
void | copyValueString< std::int8_t > (const pcl::PCLPointCloud2 &cloud, const pcl::index_t point_index, const int point_size, const unsigned int field_idx, const unsigned int fields_count, std::ostream &stream) |
template<> | |
void | copyValueString< std::uint8_t > (const pcl::PCLPointCloud2 &cloud, const pcl::index_t point_index, const int point_size, const unsigned int field_idx, const unsigned int fields_count, std::ostream &stream) |
template<typename Type > | |
std::enable_if_t< std::is_floating_point< Type >::value, bool > | isValueFinite (const pcl::PCLPointCloud2 &cloud, const pcl::index_t point_index, const int point_size, const unsigned int field_idx, const unsigned int fields_count) |
Check whether a given value of type Type (uchar, char, uint, int, float, double, ...) is finite or not. More... | |
template<typename Type > | |
std::enable_if_t< std::is_integral< Type >::value, bool > | isValueFinite (const pcl::PCLPointCloud2 &, const pcl::index_t, const int, const unsigned int, const unsigned int) |
template<typename Type > | |
void | copyStringValue (const std::string &st, pcl::PCLPointCloud2 &cloud, pcl::index_t point_index, unsigned int field_idx, unsigned int fields_count) |
Copy one single value of type T (uchar, char, uint, int, float, double, ...) from a string. More... | |
template<typename Type > | |
void | copyStringValue (const std::string &st, pcl::PCLPointCloud2 &cloud, pcl::index_t point_index, unsigned int field_idx, unsigned int fields_count, std::istringstream &is) |
Copy one single value of type T (uchar, char, uint, int, float, double, ...) from a string. More... | |
PCL_EXPORTS unsigned int | lzfCompress (const void *const in_data, unsigned int in_len, void *out_data, unsigned int out_len) |
Compress in_len bytes stored at the memory block starting at in_data and write the result to out_data, up to a maximum length of out_len bytes using Marc Lehmann's LZF algorithm. More... | |
PCL_EXPORTS unsigned int | lzfDecompress (const void *const in_data, unsigned int in_len, void *out_data, unsigned int out_len) |
Decompress data compressed with the lzfCompress function and stored at location in_data and length in_len. More... | |
template<typename SequenceSequenceT > | |
void | split (SequenceSequenceT &result, std::string const &in, const char *const delimiters) |
Lightweight tokenization function This function can be used as a boost::split substitute. More... | |
PCL_EXPORTS std::string | getTimestamp (const std::chrono::time_point< std::chrono::system_clock > &time=std::chrono::system_clock::now()) |
Returns a timestamp in local time as string formatted like boosts to_iso_string see https://www.boost.org/doc/libs/1_81_0/doc/html/date_time/posix_time.html#ptime_to_string Example: 19750101T235959.123456. More... | |
PCL_EXPORTS std::chrono::time_point< std::chrono::system_clock > | parseTimestamp (std::string timestamp) |
Parses a iso timestring (see https://www.boost.org/doc/libs/1_81_0/doc/html/date_time/posix_time.html#ptime_to_string) and returns a timepoint. More... | |
template<class FlannIndex , class Query , class Indices , class Distances , class SearchParams > | |
int | knn_search (const FlannIndex &index, const Query &query, Indices &indices, Distances &dists, unsigned int k, const SearchParams ¶ms) |
Compatibility template function to allow use of various types of indices with FLANN. More... | |
template<class FlannIndex , class Query , class Indices , class Distances , class SearchParams > | |
int | radius_search (const FlannIndex &index, const Query &query, Indices &indices, Distances &dists, float radius, const SearchParams ¶ms) |
Compatibility template function to allow use of various types of indices with FLANN. More... | |
template<typename PointT > | |
void | getApproximateIndices (const typename pcl::PointCloud< PointT >::ConstPtr &cloud_in, const typename pcl::PointCloud< PointT >::ConstPtr &cloud_ref, Indices &indices) |
Get a set of approximate indices for a given point cloud into a reference point cloud. More... | |
template<typename Point1T , typename Point2T > | |
void | getApproximateIndices (const typename pcl::PointCloud< Point1T >::ConstPtr &cloud_in, const typename pcl::PointCloud< Point2T >::ConstPtr &cloud_ref, Indices &indices) |
Get a set of approximate indices for a given point cloud into a reference point cloud. More... | |
std::ostream & | operator<< (std::ostream &os, const NarfKeypoint::Parameters &p) |
std::ostream & | operator<< (std::ostream &os, const GradientXY &p) |
template<class Type > | |
void | read (std::istream &stream, Type &value) |
Function for reading data from a stream. More... | |
template<class Type > | |
void | read (std::istream &stream, Type *value, int nr_values) |
Function for reading data arrays from a stream. More... | |
template<class Type > | |
void | write (std::ostream &stream, Type value) |
Function for writing data to a stream. More... | |
template<class Type > | |
void | write (std::ostream &stream, Type *value, int nr_values) |
Function for writing data arrays to a stream. More... | |
template<typename PointT > | |
float | getMeanPointDensity (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, float max_dist, int nr_threads=1) |
Compute the mean point density of a given point cloud. More... | |
template<typename PointT > | |
float | getMeanPointDensity (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const pcl::Indices &indices, float max_dist, int nr_threads=1) |
Compute the mean point density of a given point cloud. More... | |
template<typename Point > | |
void | projectPoint (const Point &p, const Eigen::Vector4f &model_coefficients, Point &q) |
Project a point on a planar model given by a set of normalized coefficients. More... | |
template<typename Point > | |
double | pointToPlaneDistanceSigned (const Point &p, double a, double b, double c, double d) |
Get the distance from a point to a plane (signed) defined by ax+by+cz+d=0. More... | |
template<typename Point > | |
double | pointToPlaneDistanceSigned (const Point &p, const Eigen::Vector4f &plane_coefficients) |
Get the distance from a point to a plane (signed) defined by ax+by+cz+d=0. More... | |
template<typename Point > | |
double | pointToPlaneDistance (const Point &p, double a, double b, double c, double d) |
Get the distance from a point to a plane (unsigned) defined by ax+by+cz+d=0. More... | |
template<typename Point > | |
double | pointToPlaneDistance (const Point &p, const Eigen::Vector4f &plane_coefficients) |
Get the distance from a point to a plane (unsigned) defined by ax+by+cz+d=0. More... | |
template<typename PointT > | |
void | extractEuclideanClusters (const PointCloud< PointT > &cloud, const typename search::Search< PointT >::Ptr &tree, float tolerance, std::vector< PointIndices > &clusters, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=(std::numeric_limits< int >::max)()) |
Decompose a region of space into clusters based on the Euclidean distance between points. More... | |
template<typename PointT > | |
void | extractEuclideanClusters (const PointCloud< PointT > &cloud, const Indices &indices, const typename search::Search< PointT >::Ptr &tree, float tolerance, std::vector< PointIndices > &clusters, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=(std::numeric_limits< int >::max)()) |
Decompose a region of space into clusters based on the Euclidean distance between points. More... | |
template<typename PointT , typename Normal > | |
void | extractEuclideanClusters (const PointCloud< PointT > &cloud, const PointCloud< Normal > &normals, float tolerance, const typename KdTree< PointT >::Ptr &tree, std::vector< PointIndices > &clusters, double eps_angle, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=(std::numeric_limits< int >::max)()) |
Decompose a region of space into clusters based on the euclidean distance between points, and the normal angular deviation between points. More... | |
template<typename PointT , typename Normal > | |
void | extractEuclideanClusters (const PointCloud< PointT > &cloud, const PointCloud< Normal > &normals, const Indices &indices, const typename KdTree< PointT >::Ptr &tree, float tolerance, std::vector< PointIndices > &clusters, double eps_angle, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=(std::numeric_limits< int >::max)()) |
Decompose a region of space into clusters based on the euclidean distance between points, and the normal angular deviation between points. More... | |
bool | comparePointClusters (const pcl::PointIndices &a, const pcl::PointIndices &b) |
Sort clusters method (for std::sort). More... | |
template<typename PointT > | |
void | extractLabeledEuclideanClusters (const PointCloud< PointT > &cloud, const typename search::Search< PointT >::Ptr &tree, float tolerance, std::vector< std::vector< PointIndices >> &labeled_clusters, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=std::numeric_limits< unsigned int >::max()) |
Decompose a region of space into clusters based on the Euclidean distance between points. More... | |
bool | compareLabeledPointClusters (const pcl::PointIndices &a, const pcl::PointIndices &b) |
Sort clusters method (for std::sort). More... | |
template<typename PointT > | |
bool | isPointIn2DPolygon (const PointT &point, const pcl::PointCloud< PointT > &polygon) |
General purpose method for checking if a 3D point is inside or outside a given 2D polygon. More... | |
template<typename PointT > | |
bool | isXYPointIn2DXYPolygon (const PointT &point, const pcl::PointCloud< PointT > &polygon) |
Check if a 2d point (X and Y coordinates considered only!) is inside or outside a given polygon. More... | |
template<> | |
float | squaredEuclideanDistance (const pcl::segmentation::grabcut::Color &c1, const pcl::segmentation::grabcut::Color &c2) |
bool | comparePair (std::pair< float, int > i, std::pair< float, int > j) |
This function is used as a comparator for sorting. More... | |
void | seededHueSegmentation (const PointCloud< PointXYZRGB > &cloud, const search::Search< PointXYZRGB >::Ptr &tree, float tolerance, PointIndices &indices_in, PointIndices &indices_out, float delta_hue=0.0) |
Decompose a region of space into clusters based on the Euclidean distance between points. More... | |
void | seededHueSegmentation (const PointCloud< PointXYZRGB > &cloud, const search::Search< PointXYZRGBL >::Ptr &tree, float tolerance, PointIndices &indices_in, PointIndices &indices_out, float delta_hue=0.0) |
Decompose a region of space into clusters based on the Euclidean distance between points. More... | |
template<typename PointT > | |
void | getPointCloudDifference (const pcl::PointCloud< PointT > &src, double threshold, const typename pcl::search::Search< PointT >::Ptr &tree, pcl::PointCloud< PointT > &output) |
Obtain the difference between two aligned point clouds as another point cloud, given a distance threshold. More... | |
template<class T > | |
short int | doStereoRatioFilter (const T *const acc, short int dbest, T sad_min, int ratio_filter, int maxdisp, int precision=100) |
template<class T > | |
short int | doStereoPeakFilter (const T *const acc, short int dbest, int peak_filter, int maxdisp) |
bool | comparePoints2D (const std::pair< int, Eigen::Vector4f > &p1, const std::pair< int, Eigen::Vector4f > &p2) |
Sort 2D points in a vector structure. More... | |
bool | isVisible (const Eigen::Vector2f &X, const Eigen::Vector2f &S1, const Eigen::Vector2f &S2, const Eigen::Vector2f &R=Eigen::Vector2f::Zero()) |
Returns if a point X is visible from point R (or the origin) when taking into account the segment between the points S1 and S2. More... | |
Variables | |
static constexpr index_t | UNAVAILABLE = static_cast<index_t>(-1) |
template<typename F , typename... Args> | |
constexpr bool | is_invocable_v |
template<typename R , typename F , typename... Args> | |
constexpr bool | is_invocable_r_v |
constexpr int | SAC_RANSAC = 0 |
constexpr int | SAC_LMEDS = 1 |
constexpr int | SAC_MSAC = 2 |
constexpr int | SAC_RRANSAC = 3 |
constexpr int | SAC_RMSAC = 4 |
constexpr int | SAC_MLESAC = 5 |
constexpr int | SAC_PROSAC = 6 |
const int | I_SHIFT_EP [12][2] |
The 12 edges of a cell. More... | |
const int | I_SHIFT_PT [4] |
const int | I_SHIFT_EDGE [3][2] |
const unsigned int | edgeTable [256] |
const int | triTable [256][16] |
using pcl::AlignedVector = typedef std::vector<T, Eigen::aligned_allocator<T> > |
using pcl::Array3fMap = typedef Eigen::Map<Eigen::Array3f> |
Definition at line 195 of file point_types.hpp.
using pcl::Array3fMapConst = typedef const Eigen::Map<const Eigen::Array3f> |
Definition at line 196 of file point_types.hpp.
using pcl::Array4fMap = typedef Eigen::Map<Eigen::Array4f, Eigen::Aligned> |
Definition at line 197 of file point_types.hpp.
using pcl::Array4fMapConst = typedef const Eigen::Map<const Eigen::Array4f, Eigen::Aligned> |
Definition at line 198 of file point_types.hpp.
using pcl::BivariatePolynomial = typedef BivariatePolynomialT<float> |
Definition at line 139 of file bivariate_polynomial.h.
using pcl::BivariatePolynomiald = typedef BivariatePolynomialT<double> |
Definition at line 138 of file bivariate_polynomial.h.
using pcl::Correspondences = typedef std::vector< pcl::Correspondence, Eigen::aligned_allocator<pcl::Correspondence> > |
Definition at line 89 of file correspondence.h.
using pcl::CorrespondencesConstPtr = typedef shared_ptr<const Correspondences > |
Definition at line 91 of file correspondence.h.
using pcl::CorrespondencesPtr = typedef shared_ptr<Correspondences> |
Definition at line 90 of file correspondence.h.
using pcl::Depth2DComparisonFeatureHandler = typedef MultiChannel2DComparisonFeatureHandler<float, 1> |
Definition at line 437 of file multi_channel_2d_comparison_feature_handler.h.
using pcl::Depth2DDataSet = typedef MultiChannel2DDataSet<float, 1> |
Definition at line 239 of file multi_channel_2d_data_set.h.
using pcl::GlasbeyLUT = typedef ColorLUT<pcl::LUT_GLASBEY> |
using pcl::HeaderConstPtr = typedef PCLHeader::ConstPtr |
Definition at line 27 of file PCLHeader.h.
using pcl::HeaderPtr = typedef PCLHeader::Ptr |
Definition at line 26 of file PCLHeader.h.
using pcl::index_t = typedef detail::int_type_t<detail::index_type_size, detail::index_type_signed> |
using pcl::Indices = typedef IndicesAllocator<> |
using pcl::IndicesAllocator = typedef std::vector<index_t, Allocator> |
using pcl::IndicesClusters = typedef std::vector<pcl::PointIndices> |
Definition at line 50 of file conditional_euclidean_clustering.h.
using pcl::IndicesClustersPtr = typedef shared_ptr<std::vector<pcl::PointIndices> > |
Definition at line 51 of file conditional_euclidean_clustering.h.
using pcl::IndicesConstPtr = typedef shared_ptr<const Indices> |
Definition at line 59 of file pcl_base.h.
using pcl::IndicesPtr = typedef shared_ptr<Indices> |
Definition at line 58 of file pcl_base.h.
using pcl::IntensityDepth2DComparisonFeatureHandler = typedef MultiChannel2DComparisonFeatureHandler<float, 2> |
Definition at line 439 of file multi_channel_2d_comparison_feature_handler.h.
using pcl::IntensityDepth2DDataSet = typedef MultiChannel2DDataSet<float, 2> |
Definition at line 240 of file multi_channel_2d_data_set.h.
using pcl::ModelCoefficientsConstPtr = typedef ModelCoefficients::ConstPtr |
Definition at line 25 of file ModelCoefficients.h.
using pcl::ModelCoefficientsPtr = typedef ModelCoefficients::Ptr |
Definition at line 24 of file ModelCoefficients.h.
using pcl::MsgFieldMap = typedef std::vector<detail::FieldMapping> |
Definition at line 72 of file point_cloud.h.
using pcl::PCLImageConstPtr = typedef PCLImage::ConstPtr |
Definition at line 30 of file PCLImage.h.
using pcl::PCLImagePtr = typedef PCLImage::Ptr |
Definition at line 29 of file PCLImage.h.
using pcl::PCLPointCloud2ConstPtr = typedef PCLPointCloud2::ConstPtr |
Definition at line 119 of file PCLPointCloud2.h.
using pcl::PCLPointCloud2Ptr = typedef PCLPointCloud2::Ptr |
Definition at line 118 of file PCLPointCloud2.h.
using pcl::PCLPointFieldConstPtr = typedef PCLPointField::ConstPtr |
Definition at line 38 of file PCLPointField.h.
using pcl::PCLPointFieldPtr = typedef PCLPointField::Ptr |
Definition at line 37 of file PCLPointField.h.
using pcl::PointCorrespondences3DVector = typedef std::vector<PointCorrespondence3D, Eigen::aligned_allocator<PointCorrespondence3D> > |
Definition at line 124 of file correspondence.h.
using pcl::PointCorrespondences6DVector = typedef std::vector<PointCorrespondence6D, Eigen::aligned_allocator<PointCorrespondence6D> > |
Definition at line 138 of file correspondence.h.
using pcl::PointIndicesConstPtr = typedef PointIndices::ConstPtr |
Definition at line 24 of file PointIndices.h.
using pcl::PointIndicesPtr = typedef PointIndices::Ptr |
Definition at line 23 of file PointIndices.h.
using pcl::PolygonMeshConstPtr = typedef PolygonMesh::ConstPtr |
Definition at line 101 of file PolygonMesh.h.
using pcl::PolygonMeshPtr = typedef PolygonMesh::Ptr |
Definition at line 100 of file PolygonMesh.h.
using pcl::PolynomialCalculations = typedef PolynomialCalculationsT<float> |
Definition at line 124 of file polynomial_calculations.h.
using pcl::PolynomialCalculationsd = typedef PolynomialCalculationsT<double> |
Definition at line 123 of file polynomial_calculations.h.
using pcl::remove_cvref_t = typedef std::remove_cv_t<std::remove_reference_t<T> > |
Definition at line 298 of file type_traits.h.
using pcl::RGB2DComparisonFeatureHandler = typedef MultiChannel2DComparisonFeatureHandler<float, 3> |
Definition at line 441 of file multi_channel_2d_comparison_feature_handler.h.
using pcl::RGB2DDataSet = typedef MultiChannel2DDataSet<float, 3> |
Definition at line 241 of file multi_channel_2d_data_set.h.
using pcl::RGBD2DComparisonFeatureHandler = typedef MultiChannel2DComparisonFeatureHandler<float, 4> |
Definition at line 442 of file multi_channel_2d_comparison_feature_handler.h.
using pcl::RGBD2DDataSet = typedef MultiChannel2DDataSet<float, 4> |
Definition at line 242 of file multi_channel_2d_data_set.h.
using pcl::ScaledDepth2DComparisonFeatureHandler = typedef ScaledMultiChannel2DComparisonFeatureHandler<float, 1, 0, true> |
Definition at line 444 of file multi_channel_2d_comparison_feature_handler.h.
using pcl::ScaledDepth2DComparisonFeatureHandlerCCodeGenerator = typedef ScaledMultiChannel2DComparisonFeatureHandlerCCodeGenerator<float, 1, 0, true> |
Definition at line 451 of file multi_channel_2d_comparison_feature_handler.h.
using pcl::ScaledIntensityDepth2DComparisonFeatureHandler = typedef ScaledMultiChannel2DComparisonFeatureHandler<float, 2, 1, true> |
Definition at line 446 of file multi_channel_2d_comparison_feature_handler.h.
using pcl::ScaledRGBD2DComparisonFeatureHandler = typedef ScaledMultiChannel2DComparisonFeatureHandler<float, 4, 3, true> |
Definition at line 448 of file multi_channel_2d_comparison_feature_handler.h.
using pcl::TextureMeshConstPtr = typedef TextureMesh::ConstPtr |
Definition at line 112 of file TextureMesh.h.
using pcl::TextureMeshPtr = typedef TextureMesh::Ptr |
Definition at line 111 of file TextureMesh.h.
using pcl::uindex_t = typedef detail::int_type_t<detail::index_type_size, false> |
using pcl::Vector2fMap = typedef Eigen::Map<Eigen::Vector2f> |
Definition at line 193 of file point_types.hpp.
using pcl::Vector2fMapConst = typedef const Eigen::Map<const Eigen::Vector2f> |
Definition at line 194 of file point_types.hpp.
using pcl::Vector3c = typedef Eigen::Matrix<std::uint8_t, 3, 1> |
Definition at line 204 of file point_types.hpp.
using pcl::Vector3cMap = typedef Eigen::Map<Vector3c> |
Definition at line 205 of file point_types.hpp.
using pcl::Vector3cMapConst = typedef const Eigen::Map<const Vector3c> |
Definition at line 206 of file point_types.hpp.
using pcl::Vector3fMap = typedef Eigen::Map<Eigen::Vector3f> |
Definition at line 199 of file point_types.hpp.
using pcl::Vector3fMapConst = typedef const Eigen::Map<const Eigen::Vector3f> |
Definition at line 200 of file point_types.hpp.
using pcl::Vector4c = typedef Eigen::Matrix<std::uint8_t, 4, 1> |
Definition at line 207 of file point_types.hpp.
using pcl::Vector4cMap = typedef Eigen::Map<Vector4c, Eigen::Aligned> |
Definition at line 208 of file point_types.hpp.
using pcl::Vector4cMapConst = typedef const Eigen::Map<const Vector4c, Eigen::Aligned> |
Definition at line 209 of file point_types.hpp.
using pcl::Vector4fMap = typedef Eigen::Map<Eigen::Vector4f, Eigen::Aligned> |
Definition at line 201 of file point_types.hpp.
using pcl::Vector4fMapConst = typedef const Eigen::Map<const Eigen::Vector4f, Eigen::Aligned> |
Definition at line 202 of file point_types.hpp.
using pcl::VectorAverage2f = typedef VectorAverage<float, 2> |
Definition at line 116 of file vector_average.h.
using pcl::VectorAverage3f = typedef VectorAverage<float, 3> |
Definition at line 117 of file vector_average.h.
using pcl::VectorAverage4f = typedef VectorAverage<float, 4> |
Definition at line 118 of file vector_average.h.
using pcl::VerticesConstPtr = typedef Vertices::ConstPtr |
Definition at line 27 of file Vertices.h.
using pcl::VerticesPtr = typedef Vertices::Ptr |
Definition at line 26 of file Vertices.h.
using pcl::ViridisLUT = typedef ColorLUT<pcl::LUT_VIRIDIS> |
using pcl::void_t = typedef void |
Definition at line 255 of file type_traits.h.
enum pcl::ColorLUTName |
Enumerator | |
---|---|
LUT_GLASBEY | Color lookup table consisting of 256 colors structured in a maximally discontinuous manner. Generated using the method of Glasbey et al. (see https://github.com/taketwo/glasbey) |
LUT_VIRIDIS | A perceptually uniform colormap created by Stéfan van der Walt and Nathaniel Smith for the Python matplotlib library. (see https://youtu.be/xAoljeRJ3lU for background and overview) |
Enumerator | |
---|---|
MORPH_OPEN | |
MORPH_CLOSE | |
MORPH_DILATE | |
MORPH_ERODE |
Definition at line 49 of file morphological_filter.h.
enum pcl::SacModel |
Definition at line 45 of file model_types.h.
|
inline |
Definition at line 409 of file pcl_macros.h.
Referenced by pcl::EnergyMaps::releaseAll(), and pcl::LinearizedMaps::releaseAll().
|
inline |
Definition at line 387 of file pcl_macros.h.
Referenced by pcl::EnergyMaps::initialize(), and pcl::LinearizedMaps::initialize().
void pcl::approximatePolygon | ( | const PlanarPolygon< PointT > & | polygon, |
PlanarPolygon< PointT > & | approx_polygon, | ||
float | threshold, | ||
bool | refine = false , |
||
bool | closed = true |
||
) |
see approximatePolygon2D
Definition at line 44 of file polygon_operations.hpp.
References pcl::PlanarPolygon< PointT >::getCoefficients(), pcl::PlanarPolygon< PointT >::getContour(), pcl::PointCloud< PointT >::resize(), and pcl::PointCloud< PointT >::size().
void pcl::approximatePolygon2D | ( | const typename PointCloud< PointT >::VectorType & | polygon, |
typename PointCloud< PointT >::VectorType & | approx_polygon, | ||
float | threshold, | ||
bool | refine = false , |
||
bool | closed = true |
||
) |
returns an approximate polygon to given 2D contour.
Uses just X and Y values.
[in] | polygon | input polygon |
[out] | approx_polygon | approximate polygon |
[in] | threshold | maximum allowed distance of an input vertex to an output edge |
refine | ||
[in] | closed | whether it is a closed polygon or a polyline |
Definition at line 80 of file polygon_operations.hpp.
References pcl::PointCloud< PointT >::clear(), pcl::geometry::distance(), eigen22(), M_SQRT1_2, pcl::PointCloud< PointT >::push_back(), pcl::PointCloud< PointT >::reserve(), and pcl::PointCloud< PointT >::size().
|
inline |
Check coordinate system integrity.
[in] | origin | the origin of the coordinate system |
[in] | x_direction | the first axis |
[in] | y_direction | the second axis |
[in] | norm_limit | the limit to ignore norm rounding errors |
[in] | dot_limit | the limit to ignore dot product rounding errors |
Read the other variant for more information
bool pcl::checkCoordinateSystem | ( | const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > & | line_x, |
const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > & | line_y, | ||
const Scalar | norm_limit = 1e-3 , |
||
const Scalar | dot_limit = 1e-3 |
||
) |
Check coordinate system integrity.
[in] | line_x | the first axis |
[in] | line_y | the second axis |
[in] | norm_limit | the limit to ignore norm rounding errors |
[in] | dot_limit | the limit to ignore dot product rounding errors |
Lines must be filled in this form:
line[0-2] = Origin coordinates of the vector
line[3-5] = Direction vector
Can be used like this :
line_x = X axis and line_y = Y axis
line_x = Z axis and line_y = X axis
line_x = Y axis and line_y = Z axis
Because X^Y = Z, Z^X = Y and Y^Z = X. Do NOT invert line order !
Determine whether a coordinate system is consistent or not by checking :
Line origins: They must be the same for the 2 lines
Norm: The 2 lines must be normalized
Dot products: Must be 0 or perpendicular vectors
Definition at line 798 of file eigen.hpp.
Referenced by transformBetween2CoordinateSystems().
|
inline |
This function is used as a comparator for sorting.
Definition at line 340 of file region_growing.h.
Referenced by pcl::RegionGrowingRGB< PointT, NormalT >::applyRegionMergingAlgorithm(), pcl::RegionGrowing< PointT, NormalT >::applySmoothRegionGrowingAlgorithm(), and pcl::RegionGrowingRGB< PointT, NormalT >::findRegionNeighbours().
|
inline |
Definition at line 133 of file centroid.h.
|
inline |
Definition at line 125 of file centroid.h.
|
inline |
Definition at line 164 of file centroid.h.
|
inline |
Definition at line 156 of file centroid.h.
|
inline |
Definition at line 103 of file centroid.h.
|
inline |
Definition at line 96 of file centroid.h.
|
inline |
Definition at line 77 of file centroid.h.
|
inline |
Definition at line 70 of file centroid.h.
|
inline |
Definition at line 198 of file centroid.h.
|
inline |
Definition at line 190 of file centroid.h.
|
inline |
Definition at line 268 of file centroid.h.
|
inline |
Definition at line 259 of file centroid.h.
|
inline |
Definition at line 552 of file centroid.h.
|
inline |
Definition at line 544 of file centroid.h.
|
inline |
Definition at line 305 of file centroid.h.
|
inline |
Definition at line 296 of file centroid.h.
|
inline |
Definition at line 585 of file centroid.h.
|
inline |
Definition at line 577 of file centroid.h.
|
inline |
Definition at line 520 of file centroid.h.
|
inline |
Definition at line 513 of file centroid.h.
|
inline |
Definition at line 232 of file centroid.h.
|
inline |
Definition at line 224 of file centroid.h.
|
inline |
Definition at line 344 of file centroid.h.
|
inline |
Definition at line 335 of file centroid.h.
|
inline |
Definition at line 382 of file centroid.h.
|
inline |
Definition at line 373 of file centroid.h.
PCL_EXPORTS bool pcl::computeCPPFPairFeature | ( | const Eigen::Vector4f & | p1, |
const Eigen::Vector4f & | n1, | ||
const Eigen::Vector4i & | c1, | ||
const Eigen::Vector4f & | p2, | ||
const Eigen::Vector4f & | n2, | ||
const Eigen::Vector4i & | c2, | ||
float & | f1, | ||
float & | f2, | ||
float & | f3, | ||
float & | f4, | ||
float & | f5, | ||
float & | f6, | ||
float & | f7, | ||
float & | f8, | ||
float & | f9, | ||
float & | f10 | ||
) |
[in] | p1 | |
[in] | n1 | |
[in] | p2 | |
[in] | n2 | |
[in] | c1 | |
[in] | c2 | |
[out] | f1 | |
[out] | f2 | |
[out] | f3 | |
[out] | f4 | |
[out] | f5 | |
[out] | f6 | |
[out] | f7 | |
[out] | f8 | |
[out] | f9 | |
[out] | f10 |
|
inline |
Definition at line 452 of file centroid.h.
|
inline |
Definition at line 443 of file centroid.h.
|
inline |
Definition at line 489 of file centroid.h.
|
inline |
Definition at line 480 of file centroid.h.
|
inline |
Definition at line 416 of file centroid.h.
|
inline |
Definition at line 408 of file centroid.h.
|
inlinenoexcept |
Compute the median of a list of values (fast).
See the other overloaded function for more information.
Definition at line 309 of file common.h.
References computeMedian().
|
inline |
Definition at line 972 of file centroid.h.
|
inline |
Definition at line 964 of file centroid.h.
|
inline |
Definition at line 1000 of file centroid.h.
|
inline |
Definition at line 992 of file centroid.h.
|
inline |
Definition at line 945 of file centroid.h.
|
inline |
Definition at line 938 of file centroid.h.
PCL_EXPORTS bool pcl::computePPFPairFeature | ( | const Eigen::Vector4f & | p1, |
const Eigen::Vector4f & | n1, | ||
const Eigen::Vector4f & | p2, | ||
const Eigen::Vector4f & | n2, | ||
float & | f1, | ||
float & | f2, | ||
float & | f3, | ||
float & | f4 | ||
) |
[in] | p1 | |
[in] | n1 | |
[in] | p2 | |
[in] | n2 | |
[out] | f1 | |
[out] | f2 | |
[out] | f3 | |
[out] | f4 |
PCL_EXPORTS bool pcl::computeRGBPairFeatures | ( | const Eigen::Vector4f & | p1, |
const Eigen::Vector4f & | n1, | ||
const Eigen::Vector4i & | colors1, | ||
const Eigen::Vector4f & | p2, | ||
const Eigen::Vector4f & | n2, | ||
const Eigen::Vector4i & | colors2, | ||
float & | f1, | ||
float & | f2, | ||
float & | f3, | ||
float & | f4, | ||
float & | f5, | ||
float & | f6, | ||
float & | f7 | ||
) |
|
inline |
computes the roots of the characteristic polynomial of the input matrix m, which are the eigenvalues
[in] | m | input matrix |
[out] | roots | roots of the characteristic polynomial of the input matrix m, which are the eigenvalues |
Definition at line 68 of file eigen.hpp.
References computeRoots2().
Referenced by pcl::VectorAverage< real, dimension >::doPCA(), and eigen33().
|
inline |
Compute the roots of a quadratic polynom x^2 + b*x + c = 0.
[in] | b | linear parameter |
[in] | c | constant parameter |
[out] | roots | solutions of x^2 + b*x + c = 0 |
Definition at line 53 of file eigen.hpp.
Referenced by computeRoots().
|
inline |
Copy one single value of type T (uchar, char, uint, int, float, double, ...) from a string.
Uses istringstream
to do the conversion in classic locale Checks if the st is "nan" and converts it accordingly.
[in] | st | the string containing the value to convert and copy |
[out] | cloud | the cloud to copy it to |
[in] | point_index | the index of the point |
[in] | field_idx | the index of the dimension/field |
[in] | fields_count | the current fields count |
|
inline |
Copy one single value of type T (uchar, char, uint, int, float, double, ...) from a string.
Uses the provided istringstream
to do the conversion, respecting its locale settings Checks if the st is "nan" and converts it accordingly.
[in] | st | the string containing the value to convert and copy |
[out] | cloud | the cloud to copy it to |
[in] | point_index | the index of the point |
[in] | field_idx | the index of the dimension/field |
[in] | fields_count | the current fields count |
[in,out] | is | input string stream for helping to convert st into cloud |
|
inline |
inserts a value of type Type (uchar, char, uint, int, float, double, ...) into a stringstream.
If the value is NaN, it inserts "nan".
[in] | cloud | the cloud to copy from |
[in] | point_index | the index of the point |
[in] | point_size | the size of the point in the cloud |
[in] | field_idx | the index of the dimension/field |
[in] | fields_count | the current fields count |
[out] | stream | the ostringstream to copy into |
Definition at line 237 of file file_io.h.
References pcl::PCLPointCloud2::data, and pcl::PCLPointCloud2::fields.
|
inline |
Definition at line 254 of file file_io.h.
References pcl::PCLPointCloud2::data, and pcl::PCLPointCloud2::fields.
|
inline |
Definition at line 266 of file file_io.h.
References pcl::PCLPointCloud2::data, and pcl::PCLPointCloud2::fields.
|
inline |
Definition at line 280 of file file_io.h.
References pcl::PCLPointCloud2::data, and pcl::PCLPointCloud2::fields.
void pcl::createMapping | ( | const std::vector< pcl::PCLPointField > & | msg_fields, |
MsgFieldMap & | field_map | ||
) |
Definition at line 189 of file conversions.h.
References pcl::detail::fieldOrdering().
void pcl::demeanPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const Eigen::Vector4d & | centroid, | ||
Eigen::MatrixXd & | cloud_out | ||
) |
Definition at line 822 of file centroid.h.
void pcl::demeanPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const Eigen::Vector4f & | centroid, | ||
Eigen::MatrixXf & | cloud_out | ||
) |
Definition at line 814 of file centroid.h.
void pcl::demeanPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const Indices & | indices, | ||
const Eigen::Vector4d & | centroid, | ||
Eigen::MatrixXd & | cloud_out | ||
) |
Definition at line 854 of file centroid.h.
void pcl::demeanPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const Indices & | indices, | ||
const Eigen::Vector4d & | centroid, | ||
pcl::PointCloud< PointT > & | cloud_out | ||
) |
Definition at line 728 of file centroid.h.
void pcl::demeanPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const Indices & | indices, | ||
const Eigen::Vector4f & | centroid, | ||
Eigen::MatrixXf & | cloud_out | ||
) |
Definition at line 845 of file centroid.h.
void pcl::demeanPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const Indices & | indices, | ||
const Eigen::Vector4f & | centroid, | ||
pcl::PointCloud< PointT > & | cloud_out | ||
) |
Definition at line 719 of file centroid.h.
void pcl::demeanPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const pcl::PointIndices & | indices, | ||
const Eigen::Vector4d & | centroid, | ||
Eigen::MatrixXd & | cloud_out | ||
) |
Definition at line 887 of file centroid.h.
void pcl::demeanPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const pcl::PointIndices & | indices, | ||
const Eigen::Vector4d & | centroid, | ||
pcl::PointCloud< PointT > & | cloud_out | ||
) |
Definition at line 759 of file centroid.h.
void pcl::demeanPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const pcl::PointIndices & | indices, | ||
const Eigen::Vector4f & | centroid, | ||
Eigen::MatrixXf & | cloud_out | ||
) |
Definition at line 878 of file centroid.h.
void pcl::demeanPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const pcl::PointIndices & | indices, | ||
const Eigen::Vector4f & | centroid, | ||
pcl::PointCloud< PointT > & | cloud_out | ||
) |
Definition at line 750 of file centroid.h.
void pcl::demeanPointCloud | ( | ConstCloudIterator< PointT > & | cloud_iterator, |
const Eigen::Vector4d & | centroid, | ||
Eigen::MatrixXd & | cloud_out, | ||
int | npts = 0 |
||
) |
Definition at line 792 of file centroid.h.
void pcl::demeanPointCloud | ( | ConstCloudIterator< PointT > & | cloud_iterator, |
const Eigen::Vector4d & | centroid, | ||
pcl::PointCloud< PointT > & | cloud_out | ||
) |
Definition at line 698 of file centroid.h.
void pcl::demeanPointCloud | ( | ConstCloudIterator< PointT > & | cloud_iterator, |
const Eigen::Vector4d & | centroid, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
int | npts = 0 |
||
) |
Definition at line 670 of file centroid.h.
void pcl::demeanPointCloud | ( | ConstCloudIterator< PointT > & | cloud_iterator, |
const Eigen::Vector4f & | centroid, | ||
Eigen::MatrixXf & | cloud_out, | ||
int | npts = 0 |
||
) |
Definition at line 783 of file centroid.h.
void pcl::demeanPointCloud | ( | ConstCloudIterator< PointT > & | cloud_iterator, |
const Eigen::Vector4f & | centroid, | ||
pcl::PointCloud< PointT > & | cloud_out | ||
) |
Definition at line 690 of file centroid.h.
void pcl::demeanPointCloud | ( | ConstCloudIterator< PointT > & | cloud_iterator, |
const Eigen::Vector4f & | centroid, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
int | npts = 0 |
||
) |
Definition at line 661 of file centroid.h.
|
inline |
Definition at line 68 of file stereo_matching.h.
short int pcl::doStereoRatioFilter | ( | const T *const | acc, |
short int | dbest, | ||
T | sad_min, | ||
int | ratio_filter, | ||
int | maxdisp, | ||
int | precision = 100 |
||
) |
Definition at line 48 of file stereo_matching.h.
double pcl::estimateProjectionMatrix | ( | typename pcl::PointCloud< PointT >::ConstPtr | cloud, |
Eigen::Matrix< float, 3, 4, Eigen::RowMajor > & | projection_matrix, | ||
const Indices & | indices = {} |
||
) |
Estimates the projection matrix P = K * (R|-R*t) from organized point clouds, with K = [[fx, s, cx], [0, fy, cy], [0, 0, 1]] R = rotation matrix and t = translation vector
[in] | cloud | input cloud. Must be organized and from a projective device. e.g. stereo or kinect, ... |
[out] | projection_matrix | output projection matrix |
[in] | indices | The indices to be used to determine the projection matrix |
Definition at line 83 of file projection_matrix.hpp.
References B, pcl::ConstCloudIterator< PointT >::getCurrentPointIndex(), pcl::PointCloud< PointT >::height, pcl::common::internal::makeSymmetric(), and pcl::PointCloud< PointT >::width.
|
inline |
Calculate the euclidean distance between the two given points.
[in] | p1 | the first point |
[in] | p2 | the second point |
Definition at line 204 of file distances.h.
References squaredEuclideanDistance().
Referenced by pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::bruteForceCorrespondences(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::checkBaseMatch(), pcl::ESFEstimation< PointInT, PointOutT >::computeESF(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::determineBaseMatches(), pcl::ESFEstimation< PointInT, PointOutT >::scale_points_unit_sphere(), pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::selectSamples(), and pcl::TextureMapping< PointInT >::showOcclusions().
|
inline |
Definition at line 91 of file for_each_type.h.
void pcl::fromPCLPointCloud2 | ( | const pcl::PCLPointCloud2 & | msg, |
pcl::PointCloud< PointT > & | cloud | ||
) |
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object.
[in] | msg | the PCLPointCloud2 binary blob |
[out] | cloud | the resultant pcl::PointCloud<T> |
Definition at line 320 of file conversions.h.
References pcl::PCLPointCloud2::fields, and fromPCLPointCloud2().
void pcl::fromPCLPointCloud2 | ( | const pcl::PCLPointCloud2 & | msg, |
pcl::PointCloud< PointT > & | cloud, | ||
const MsgFieldMap & | field_map | ||
) |
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
[in] | msg | the PCLPointCloud2 binary blob |
[out] | cloud | the resultant pcl::PointCloud<T> |
[in] | field_map | a MsgFieldMap object |
Definition at line 309 of file conversions.h.
References pcl::PCLPointCloud2::data, and fromPCLPointCloud2().
void pcl::fromPCLPointCloud2 | ( | const pcl::PCLPointCloud2 & | msg, |
pcl::PointCloud< PointT > & | cloud, | ||
const MsgFieldMap & | field_map, | ||
const std::uint8_t * | msg_data | ||
) |
Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud<T> object using a field_map.
[in] | msg | the PCLPointCloud2 binary blob (note that the binary point data in msg.data will not be used!) |
[out] | cloud | the resultant pcl::PointCloud<T> |
[in] | field_map | a MsgFieldMap object |
[in] | msg_data | pointer to binary blob data, used instead of msg.data |
Definition at line 229 of file conversions.h.
References pcl::PointCloud< PointT >::data(), pcl::PCLPointCloud2::fields, pcl::PCLPointCloud2::header, pcl::PointCloud< PointT >::header, pcl::PCLPointCloud2::height, pcl::PointCloud< PointT >::height, pcl::PCLPointCloud2::is_dense, pcl::PointCloud< PointT >::is_dense, pcl::PCLPointCloud2::point_step, pcl::PointCloud< PointT >::resize(), pcl::PCLPointCloud2::row_step, pcl::PCLPointCloud2::width, and pcl::PointCloud< PointT >::width.
Referenced by fromPCLPointCloud2(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::getMeshesFromTSDFVector(), pcl::TextureMapping< PointInT >::mapMultipleTexturesToMeshUV(), pcl::ImageGrabber< PointT >::operator[](), pcl::PCDGrabber< PointT >::operator[](), pcl::ImageGrabber< PointT >::publish(), pcl::StereoGrabber< PointT >::publish(), pcl::PCDGrabber< PointT >::publish(), pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes(), pcl::IFSReader::read(), pcl::FileReader::read(), pcl::OBJReader::read(), pcl::PCDReader::read(), pcl::PLYReader::read(), pcl::TextureMapping< PointInT >::removeOccludedPoints(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::runMarchingCubes(), pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::setSourceNormals(), pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::setSourceNormals(), pcl::registration::CorrespondenceRejectorSurfaceNormal::setSourceNormals(), pcl::registration::CorrespondenceRejectorDistance::setSourcePoints(), pcl::registration::CorrespondenceRejectorMedianDistance::setSourcePoints(), pcl::registration::CorrespondenceRejectionOrganizedBoundary::setSourcePoints(), pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::setSourcePoints(), pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::setSourcePoints(), pcl::registration::CorrespondenceRejectorSurfaceNormal::setSourcePoints(), pcl::registration::CorrespondenceRejectorVarTrimmed::setSourcePoints(), pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::setTargetNormals(), pcl::registration::CorrespondenceRejectorSurfaceNormal::setTargetNormals(), pcl::registration::CorrespondenceRejectorDistance::setTargetPoints(), pcl::registration::CorrespondenceRejectorMedianDistance::setTargetPoints(), pcl::registration::CorrespondenceRejectionOrganizedBoundary::setTargetPoints(), pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::setTargetPoints(), pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::setTargetPoints(), pcl::registration::CorrespondenceRejectorSurfaceNormal::setTargetPoints(), pcl::registration::CorrespondenceRejectorVarTrimmed::setTargetPoints(), pcl::TextureMapping< PointInT >::showOcclusions(), pcl::TextureMapping< PointInT >::sortFacesByCamera(), pcl::TextureMapping< PointInT >::textureMeshwithMultipleCameras(), and pcl::geometry::toHalfEdgeMesh().
|
inline |
Find all *.pcd files in the directory and return them sorted.
directory | the directory to be searched |
file_names | the resulting (sorted) list of .pcd files |
Definition at line 55 of file file_io.hpp.
PCL_EXPORTS void pcl::getCameraMatrixFromProjectionMatrix | ( | const Eigen::Matrix< float, 3, 4, Eigen::RowMajor > & | projection_matrix, |
Eigen::Matrix3f & | camera_matrix | ||
) |
Determines the camera matrix from the given projection matrix.
[in] | projection_matrix | |
[out] | camera_matrix |
Referenced by pcl::search::OrganizedNeighbor< PointT >::computeCameraMatrix().
int pcl::getFieldIndex | ( | const pcl::PointCloud< PointT > & | , |
const std::string & | field_name, | ||
std::vector< pcl::PCLPointField > & | fields | ||
) |
Definition at line 52 of file io.hpp.
Referenced by pcl::OrganizedFastMesh< PointInT >::performReconstruction(), and pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::sortOctantIndices().
void pcl::getFields | ( | const pcl::PointCloud< PointT > & | , |
std::vector< pcl::PCLPointField > & | fields | ||
) |
void pcl::getFields | ( | std::vector< pcl::PCLPointField > & | fields | ) |
PCL_EXPORTS void pcl::getFieldsSizes | ( | const std::vector< pcl::PCLPointField > & | fields, |
std::vector< int > & | field_sizes | ||
) |
Obtain a vector with the sizes of all valid fields (e.g., not "_")
[in] | fields | the input vector containing the fields |
[out] | field_sizes | the resultant field sizes in bytes |
|
inline |
Get the value at a specified field in a point.
[in] | pt | the point to get the value from |
[in] | field_offset | the offset of the field |
[out] | value | the value to retrieve |
Definition at line 249 of file type_traits.h.
|
inline |
Get the file extension from the given string (the remaining string after the last '.
')
input | the input filename |
Definition at line 89 of file file_io.hpp.
|
inline |
Remove the extension from the given string and return only the filename (everything before the last '.
')
input | the input filename (with the file extension) |
Definition at line 83 of file file_io.hpp.
|
inline |
Remove the path from the given string and return only the filename (the remaining string after the last '/')
input | the input filename (with full path) |
Definition at line 77 of file file_io.hpp.
|
inline |
Compute the mean point density of a given point cloud.
[in] | cloud | pointer to the input point cloud |
[in] | indices | the vector of point indices to use from cloud |
[in] | max_dist | maximum distance of a point to be considered as a neighbor |
[in] | nr_threads | number of threads to use (default = 1, only used if OpenMP flag is set) |
Definition at line 87 of file ia_fpcs.hpp.
References pcl::utils::ignore(), and pcl::search::KdTree< PointT, Tree >::setInputCloud().
|
inline |
Compute the mean point density of a given point cloud.
[in] | cloud | pointer to the input point cloud |
[in] | max_dist | maximum distance of a point to be considered as a neighbor |
[in] | nr_threads | number of threads to use (default = 1, only used if OpenMP flag is set) |
Definition at line 54 of file ia_fpcs.hpp.
References pcl::utils::ignore(), pcl::search::KdTree< PointT, Tree >::nearestKSearch(), pcl::search::KdTree< PointT, Tree >::setInputCloud(), and pcl::PointCloud< PointT >::size().
PCL_EXPORTS void pcl::getMinMax3D | ( | const pcl::PCLPointCloud2ConstPtr & | cloud, |
const Indices & | indices, | ||
int | x_idx, | ||
int | y_idx, | ||
int | z_idx, | ||
const std::string & | distance_field_name, | ||
float | min_distance, | ||
float | max_distance, | ||
Eigen::Vector4f & | min_pt, | ||
Eigen::Vector4f & | max_pt, | ||
bool | limit_negative = false |
||
) |
Obtain the maximum and minimum points in 3D from a given point cloud.
[in] | cloud | the pointer to a pcl::PCLPointCloud2 dataset |
[in] | indices | the point cloud indices that need to be considered |
[in] | x_idx | the index of the X channel |
[in] | y_idx | the index of the Y channel |
[in] | z_idx | the index of the Z channel |
[in] | distance_field_name | the name of the dimension to filter data along to |
[in] | min_distance | the minimum acceptable value in distance_field_name data |
[in] | max_distance | the maximum acceptable value in distance_field_name data |
[out] | min_pt | the minimum data point |
[out] | max_pt | the maximum data point |
[in] | limit_negative | false if data inside of the [min_distance; max_distance] interval should be considered, true otherwise. |
PCL_EXPORTS void pcl::getMinMax3D | ( | const pcl::PCLPointCloud2ConstPtr & | cloud, |
const Indices & | indices, | ||
int | x_idx, | ||
int | y_idx, | ||
int | z_idx, | ||
Eigen::Vector4f & | min_pt, | ||
Eigen::Vector4f & | max_pt | ||
) |
Obtain the maximum and minimum points in 3D from a given point cloud.
[in] | cloud | the pointer to a pcl::PCLPointCloud2 dataset |
[in] | indices | the point cloud indices that need to be considered |
[in] | x_idx | the index of the X channel |
[in] | y_idx | the index of the Y channel |
[in] | z_idx | the index of the Z channel |
[out] | min_pt | the minimum data point |
[out] | max_pt | the maximum data point |
PCL_EXPORTS void pcl::getMinMax3D | ( | const pcl::PCLPointCloud2ConstPtr & | cloud, |
int | x_idx, | ||
int | y_idx, | ||
int | z_idx, | ||
const std::string & | distance_field_name, | ||
float | min_distance, | ||
float | max_distance, | ||
Eigen::Vector4f & | min_pt, | ||
Eigen::Vector4f & | max_pt, | ||
bool | limit_negative = false |
||
) |
Obtain the maximum and minimum points in 3D from a given point cloud.
[in] | cloud | the pointer to a pcl::PCLPointCloud2 dataset |
[in] | x_idx | the index of the X channel |
[in] | y_idx | the index of the Y channel |
[in] | z_idx | the index of the Z channel |
[in] | distance_field_name | the name of the dimension to filter data along to |
[in] | min_distance | the minimum acceptable value in distance_field_name data |
[in] | max_distance | the maximum acceptable value in distance_field_name data |
[out] | min_pt | the minimum data point |
[out] | max_pt | the maximum data point |
[in] | limit_negative | false if data inside of the [min_distance; max_distance] interval should be considered, true otherwise. |
PCL_EXPORTS void pcl::getMinMax3D | ( | const pcl::PCLPointCloud2ConstPtr & | cloud, |
int | x_idx, | ||
int | y_idx, | ||
int | z_idx, | ||
Eigen::Vector4f & | min_pt, | ||
Eigen::Vector4f & | max_pt | ||
) |
Obtain the maximum and minimum points in 3D from a given point cloud.
[in] | cloud | the pointer to a pcl::PCLPointCloud2 dataset |
[in] | x_idx | the index of the X channel |
[in] | y_idx | the index of the Y channel |
[in] | z_idx | the index of the Z channel |
[out] | min_pt | the minimum data point |
[out] | max_pt | the maximum data point |
|
inline |
Definition at line 499 of file transforms.h.
|
inline |
Calculates the principal (PCA-based) alignment of the point cloud.
[in] | cloud | the input point cloud |
[out] | transform | the resultant transform |
Definition at line 495 of file transforms.hpp.
References computeMeanAndCovarianceMatrix(), and eigen33().
PCL_EXPORTS RGB pcl::getRandomColor | ( | double | min = 0.2 , |
double | max = 2.8 |
||
) |
void pcl::getRejectedQueryIndices | ( | const pcl::Correspondences & | correspondences_before, |
const pcl::Correspondences & | correspondences_after, | ||
Indices & | indices, | ||
bool | presorting_required = true |
||
) |
Get the query points of correspondences that are present in one correspondence vector but not in the other, e.g., to compare correspondences before and after rejection.
[in] | correspondences_before | Vector of correspondences before rejection |
[in] | correspondences_after | Vector of correspondences after rejection |
[out] | indices | Query point indices of correspondences that have been rejected |
[in] | presorting_required | Enable/disable internal sorting of vectors. By default (true), vectors are internally sorted before determining their difference. If the order of correspondences in correspondences_after is not different (has not been changed) from the order in correspondences_before this pre-processing step can be disabled in order to gain efficiency. In order to disable pre-sorting set presorting_required to false. |
Referenced by pcl::registration::CorrespondenceRejector::getRejectedQueryIndices().
|
inline |
Returns a timestamp in local time as string formatted like boosts to_iso_string see https://www.boost.org/doc/libs/1_81_0/doc/html/date_time/posix_time.html#ptime_to_string Example: 19750101T235959.123456.
time | std::chrono::timepoint to convert, defaults to now |
Definition at line 25 of file timestamp.h.
|
inline |
|
inline |
PCL_EXPORTS int pcl::interpolatePointIndex | ( | int | p, |
int | length, | ||
InterpolationType | type | ||
) |
p | the index of point to interpolate |
length | the top/bottom row or left/right column index |
type | the requested interpolation |
pcl::BadArgumentException | if type is unknown |
Referenced by copyPointCloud().
|
inline |
Tests if the 3D components of a point are all finite param[in] pt point to be tested return true if finite, false otherwise.
Definition at line 55 of file point_tests.h.
Referenced by pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointIdx(), pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointsFromInputCloud(), pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::io::OrganizedPointCloudCompression< PointT >::analyzeOrganizedCloud(), pcl::CropBox< PointT >::applyFilter(), pcl::MedianFilter< PointT >::applyFilter(), pcl::LocalMaximum< PointT >::applyFilterIndices(), pcl::ModelOutlierRemoval< PointT >::applyFilterIndices(), pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT >::approxNearestSearch(), pcl::BriskKeypoint2D< PointInT, PointOutT, IntensityT >::bilinearInterpolation(), pcl::PyramidFeatureHistogram< PointFeature >::compute(), pcl::filters::Pyramid< PointT >::compute(), compute3DCentroid(), pcl::GrabCut< PointT >::computeBetaNonOrganized(), computeCentroid(), computeCentroidAndOBB(), computeCovarianceMatrix(), pcl::SHOTEstimation< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::computeFeature(), pcl::MomentInvariantsEstimation< PointInT, PointOutT >::computeFeature(), pcl::NormalEstimation< PointInT, PointOutT >::computeFeature(), pcl::PFHEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::computeFeature(), computeMeanAndCovarianceMatrix(), pcl::FLARELocalReferenceFrameEstimation< PointInT, PointNT, PointOutT, SignedDistanceT >::computePointLRF(), pcl::PFHEstimation< PointInT, PointNT, PointOutT >::computePointPFHSignature(), pcl::io::OrganizedConversion< PointT, true >::convert(), pcl::io::OrganizedConversion< PointT, false >::convert(), pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::convolve(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::BriskKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >::determineCorrespondences(), pcl::RangeImage::doZBuffer(), pcl::io::PointCloudImageExtractor< PointT >::extract(), pcl::ApproximateProgressiveMorphologicalFilter< PointT >::extract(), pcl::io::PointCloudImageExtractorFromLabelField< PointT >::extractImpl(), pcl::RegionGrowing< PointT, NormalT >::findPointNeighbours(), flipNormalTowardsNormalsMean(), pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::genOctreeKeyforPoint(), pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::getBoundaryPoints(), pcl::visualization::PointCloudColorHandlerLabelField< PointT >::getColor(), getPointCloudDifference(), pcl::OrganizedFastMesh< PointInT >::isValidQuad(), pcl::OrganizedFastMesh< PointInT >::isValidTriangle(), pcl::search::OrganizedNeighbor< PointT >::nearestKSearch(), pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT >::nearestKSearch(), pcl::search::BruteForce< PointT >::nearestKSearch(), pcl::filters::GaussianKernel< PointInT, PointOutT >::operator()(), pcl::filters::GaussianKernelRGB< PointInT, PointOutT >::operator()(), pcl::OrganizedFastMesh< PointInT >::performReconstruction(), pcl::io::pointCloudTovtkStructuredGrid(), pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT >::radiusSearch(), pcl::search::OrganizedNeighbor< PointT >::radiusSearch(), pcl::search::BruteForce< PointT >::radiusSearch(), removeNaNNormalsFromPointCloud(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseHarris(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseLowe(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseNoble(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseTomasi(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::responseTomasi(), pcl::search::OrganizedNeighbor< PointT >::setInputCloud(), pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT >::setOccupiedVoxelsAtPointsFromCloud(), pcl::visualization::PCLVisualizer::updatePolygonMesh(), and pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT >::voxelSearch().
|
inline |
Definition at line 68 of file point_tests.h.
|
inline |
Definition at line 70 of file point_tests.h.
|
inline |
Definition at line 71 of file point_tests.h.
|
inline |
Definition at line 69 of file point_tests.h.
|
inline |
Definition at line 72 of file point_tests.h.
|
inline |
Definition at line 73 of file point_tests.h.
|
inline |
Definition at line 74 of file point_tests.h.
|
inline |
Definition at line 75 of file point_tests.h.
|
inline |
Definition at line 77 of file point_tests.h.
|
inline |
Definition at line 76 of file point_tests.h.
|
inline |
Definition at line 78 of file point_tests.h.
|
inline |
Definition at line 79 of file point_tests.h.
|
inline |
Definition at line 80 of file point_tests.h.
|
inline |
Definition at line 81 of file point_tests.h.
|
inline |
Definition at line 82 of file point_tests.h.
|
inline |
Definition at line 111 of file point_tests.h.
|
inline |
Definition at line 83 of file point_tests.h.
|
inline |
Definition at line 84 of file point_tests.h.
|
inline |
Definition at line 85 of file point_tests.h.
|
inline |
Definition at line 104 of file point_tests.h.
References pcl::PointXY::x, and pcl::PointXY::y.
|
inline |
Definition at line 86 of file point_tests.h.
|
inline |
Definition at line 88 of file point_tests.h.
References pcl::PPFSignature::alpha_m, pcl::PPFSignature::f1, pcl::PPFSignature::f2, pcl::PPFSignature::f3, and pcl::PPFSignature::f4.
|
inline |
Definition at line 93 of file point_tests.h.
|
inline |
Definition at line 94 of file point_tests.h.
|
inline |
Definition at line 96 of file point_tests.h.
|
inline |
Definition at line 95 of file point_tests.h.
|
inline |
Definition at line 99 of file point_tests.h.
|
inline |
Definition at line 97 of file point_tests.h.
|
inline |
Definition at line 98 of file point_tests.h.
|
inline |
Definition at line 100 of file point_tests.h.
|
inline |
Definition at line 101 of file point_tests.h.
|
inlineconstexprnoexcept |
Definition at line 131 of file point_tests.h.
Referenced by pcl::visualization::PCLVisualizer::addPointCloudNormals(), and pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::computePoint().
|
inlinenoexcept |
Definition at line 150 of file point_tests.h.
|
constexprnoexcept |
|
inline |
|
inline |
Check whether a given value of type Type (uchar, char, uint, int, float, double, ...) is finite or not.
[in] | cloud | the cloud that contains the data |
[in] | point_index | the index of the point |
[in] | point_size | the size of the point in the cloud |
[in] | field_idx | the index of the dimension/field |
[in] | fields_count | the current fields count |
Definition at line 306 of file file_io.h.
References pcl::PCLPointCloud2::data, and pcl::PCLPointCloud2::fields.
|
inlineconstexprnoexcept |
Definition at line 119 of file point_tests.h.
|
inlinenoexcept |
Definition at line 138 of file point_tests.h.
|
inlineconstexprnoexcept |
Definition at line 125 of file point_tests.h.
Referenced by pcl::UniformSampling< PointT >::applyFilter(), pcl::ApproximateVoxelGrid< PointT >::applyFilter(), pcl::BilateralFilter< PointT >::applyFilter(), pcl::VoxelGrid< PointT >::applyFilter(), pcl::VoxelGridCovariance< PointT >::applyFilter(), pcl::GridMinimum< PointT >::applyFilterIndices(), pcl::RadiusOutlierRemoval< PointT >::applyFilterIndices(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::determineCorrespondences(), pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::determineReciprocalCorrespondences(), pcl::visualization::PointCloudColorHandlerRGBField< PointT >::getColor(), pcl::visualization::PointCloudColorHandlerHSVField< PointT >::getColor(), pcl::visualization::PointCloudColorHandlerGenericField< PointT >::getColor(), pcl::visualization::PointCloudColorHandlerRGBAField< PointT >::getColor(), pcl::Registration< PointSource, PointTarget, Scalar >::getFitnessScore(), getMinMax3D(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::GridProjection< PointNT >::reconstructPolygons(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseHarris(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseLowe(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseNoble(), and pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseTomasi().
|
inlinenoexcept |
Definition at line 144 of file point_tests.h.
int pcl::knn_search | ( | const FlannIndex & | index, |
const Query & | query, | ||
Indices & | indices, | ||
Distances & | dists, | ||
unsigned int | k, | ||
const SearchParams & | params | ||
) |
Compatibility template function to allow use of various types of indices with FLANN.
Template is used for all params to not constrain any FLANN side capability
[in,out] | index | A index searcher, of type ::flann::Index<Dist> or similar, where Dist is a template for computing distance between 2 points |
[in] | query | A ::flann::Matrix<float> or compatible matrix representation of the query point |
[out] | indices | Neighboring k indices found |
[out] | dists | Computed distance matrix |
[in] | k | Number of neighbors to search for |
[in] | params | Any parameters to pass to the knn_search call |
Definition at line 223 of file kdtree_flann.hpp.
Referenced by pcl::search::FlannSearch< PointT, FlannDistance >::nearestKSearch().
PCL_EXPORTS unsigned int pcl::lzfCompress | ( | const void *const | in_data, |
unsigned int | in_len, | ||
void * | out_data, | ||
unsigned int | out_len | ||
) |
Compress in_len bytes stored at the memory block starting at in_data and write the result to out_data, up to a maximum length of out_len bytes using Marc Lehmann's LZF algorithm.
If the output buffer is not large enough or any error occurs return 0, otherwise return the number of bytes used, which might be considerably more than in_len (but less than 104% of the original size), so it makes sense to always use out_len == in_len - 1), to ensure some compression, and store the data uncompressed otherwise (with a flag, of course.
[in] | in_data | the input uncompressed buffer |
[in] | in_len | the length of the input buffer |
[out] | out_data | the output buffer where the compressed result will be stored |
[in] | out_len | the length of the output buffer |
Referenced by pcl::PCDWriter::writeBinaryCompressed().
PCL_EXPORTS unsigned int pcl::lzfDecompress | ( | const void *const | in_data, |
unsigned int | in_len, | ||
void * | out_data, | ||
unsigned int | out_len | ||
) |
Decompress data compressed with the lzfCompress function and stored at location in_data and length in_len.
The result will be stored at out_data up to a maximum of out_len characters.
If the output buffer is not large enough to hold the decompressed data, a 0 is returned and errno is set to E2BIG. Otherwise the number of decompressed bytes (i.e. the original length of the data) is returned.
If an error in the compressed data is detected, a zero is returned and errno is set to EINVAL.
This function is very fast, about as fast as a copying loop.
[in] | in_data | the input compressed buffer |
[in] | in_len | the length of the input buffer |
[out] | out_data | the output buffer (must be resized to out_len) |
[in] | out_len | the length of the output buffer |
shared_ptr<T> pcl::make_shared | ( | Args &&... | args | ) |
Returns a pcl::shared_ptr compliant with type T's allocation policy.
std::allocate_shared or std::make_shared will be invoked in case T has or doesn't have a custom allocator, respectively.
T | Type of the object to create a pcl::shared_ptr of |
Args | Types for the arguments to pcl::make_shared |
args | List of arguments with which an instance of T will be constructed |
Referenced by pcl::IterativeClosestPointWithNormals< PointSource, PointTarget, Scalar >::setUseSymmetricObjective().
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const Axis & | p | ||
) |
std::ostream & pcl::operator<< | ( | std::ostream & | os, |
const BivariatePolynomialT< real > & | p | ||
) |
Definition at line 237 of file bivariate_polynomial.hpp.
References pcl::BivariatePolynomialT< real >::degree, and pcl::BivariatePolynomialT< real >::parameters.
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const BorderDescription & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const Boundary & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const BRISKSignature512 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const Correspondence & | c | ||
) |
overloaded << operator
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const CPPFSignature & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const ESFSignature640 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const FPFHSignature33 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const GASDSignature512 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const GASDSignature7992 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const GASDSignature984 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const GFPFHSignature16 & | p | ||
) |
|
inline |
Definition at line 72 of file point_types.h.
References pcl::GradientXY::magnitude, pcl::GradientXY::x, and pcl::GradientXY::y.
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const GRSDSignature21 & | p | ||
) |
std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const Histogram< N > & | p | ||
) |
Definition at line 1717 of file point_types.hpp.
References pcl::Histogram< N >::histogram, and PCL_IF_CONSTEXPR.
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const Intensity & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const Intensity32u & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const Intensity8u & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const IntensityGradient & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const InterestPoint & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const Label & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const MomentInvariants & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const Narf36 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const Normal & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const NormalBasedSignature12 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PFHRGBSignature250 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PFHSignature125 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointDEM & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointNormal & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointSurfel & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointUV & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointWithRange & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointWithScale & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointWithViewpoint & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointXY & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointXYZ & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointXYZHSV & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointXYZI & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointXYZINormal & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointXYZL & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointXYZLAB & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointXYZLNormal & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointXYZRGB & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointXYZRGBA & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointXYZRGBL & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PointXYZRGBNormal & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PPFRGBSignature & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PPFSignature & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PrincipalCurvatures & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const PrincipalRadiiRSD & | p | ||
) |
|
inline |
/ingroup range_image
Definition at line 813 of file range_image.h.
References pcl::RangeImage::getAngularResolutionX(), pcl::RangeImage::getAngularResolutionY(), pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, RAD2DEG, pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.
|
inline |
Definition at line 60 of file range_image_border_extractor.hpp.
References pcl::RangeImageBorderExtractor::Parameters::minimum_border_probability, pcl::RangeImageBorderExtractor::Parameters::pixel_radius_border_direction, pcl::RangeImageBorderExtractor::Parameters::pixel_radius_borders, pcl::RangeImageBorderExtractor::Parameters::pixel_radius_plane_extraction, pcl::RangeImageBorderExtractor::Parameters::pixel_radius_principal_curvature, PVARC, and PVARN.
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const ReferenceFrame & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const RGB & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const ShapeContext1980 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const SHOT1344 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const SHOT352 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const UniqueShapeContext1960 & | p | ||
) |
PCL_EXPORTS std::ostream& pcl::operator<< | ( | std::ostream & | os, |
const VFHSignature308 & | p | ||
) |
|
inline |
Definition at line 29 of file PCLHeader.h.
References pcl::PCLHeader::frame_id, pcl::PCLHeader::seq, and pcl::PCLHeader::stamp.
|
inline |
Definition at line 27 of file ModelCoefficients.h.
|
inline |
Definition at line 32 of file PCLImage.h.
|
inline |
Definition at line 121 of file PCLPointCloud2.h.
|
inline |
Definition at line 40 of file PCLPointField.h.
|
inline |
Definition at line 26 of file PointIndices.h.
|
inline |
Definition at line 103 of file PolygonMesh.h.
|
inline |
Definition at line 29 of file Vertices.h.
std::ostream& pcl::operator<< | ( | std::ostream & | s, |
const pcl::PointCloud< PointT > & | p | ||
) |
Definition at line 904 of file point_cloud.h.
References pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.
Definition at line 37 of file PCLHeader.h.
References pcl::PCLHeader::frame_id, pcl::PCLHeader::seq, and pcl::PCLHeader::stamp.
|
inline |
Parses a iso timestring (see https://www.boost.org/doc/libs/1_81_0/doc/html/date_time/posix_time.html#ptime_to_string) and returns a timepoint.
timestamp | as string formatted like boost iso date |
Definition at line 52 of file timestamp.h.
bool pcl::planeWithPlaneIntersection | ( | const Eigen::Matrix< Scalar, 4, 1 > & | plane_a, |
const Eigen::Matrix< Scalar, 4, 1 > & | plane_b, | ||
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > & | line, | ||
double | angular_tolerance = 0.1 |
||
) |
Determine the line of intersection of two non-parallel planes using lagrange multipliers.
[in] | plane_a | coefficients of plane A and plane B in the form ax + by + cz + d = 0 |
[in] | plane_b | coefficients of line where line.tail<3>() = direction vector and line.head<3>() the point on the line closest to (0, 0, 0) |
[out] | line | the intersected line to be filled |
[in] | angular_tolerance | tolerance in radians |
Definition at line 79 of file intersections.hpp.
|
inline |
Definition at line 105 of file intersections.h.
|
inline |
Definition at line 96 of file intersections.h.
|
inline |
Convert registered Depth image and RGB image to PointCloudXYZRGBA.
[in] | depth | the input depth image as intensity points in float |
[in] | image | the input RGB image |
[in] | focal | the focal length |
[out] | out | the output pointcloud |
Definition at line 429 of file point_types_conversion.h.
References pcl::PointCloud< PointT >::at(), pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::push_back(), and pcl::PointCloud< PointT >::width.
|
inline |
Convert a RGB point cloud to an Intensity.
Definition at line 301 of file point_types_conversion.h.
References pcl::PointCloud< PointT >::height, PointRGBtoI(), pcl::PointCloud< PointT >::push_back(), and pcl::PointCloud< PointT >::width.
|
inline |
Convert a RGB point cloud to an Intensity.
Definition at line 337 of file point_types_conversion.h.
References pcl::PointCloud< PointT >::height, PointRGBtoI(), pcl::PointCloud< PointT >::push_back(), and pcl::PointCloud< PointT >::width.
|
inline |
Convert a RGB point cloud to an Intensity.
Definition at line 319 of file point_types_conversion.h.
References pcl::PointCloud< PointT >::height, PointRGBtoI(), pcl::PointCloud< PointT >::push_back(), and pcl::PointCloud< PointT >::width.
|
inline |
Convert a XYZHSV point cloud to a XYZRGB.
[in] | in | the input XYZHSV point cloud |
[out] | out | the output XYZRGB point cloud |
Definition at line 373 of file point_types_conversion.h.
References pcl::PointCloud< PointT >::height, PointXYZHSVtoXYZRGB(), pcl::PointCloud< PointT >::push_back(), and pcl::PointCloud< PointT >::width.
|
inline |
Convert a XYZRGB point cloud to a XYZHSV.
[in] | in | the input XYZRGB point cloud |
[out] | out | the output XYZHSV point cloud |
Definition at line 391 of file point_types_conversion.h.
References pcl::PointCloud< PointT >::height, PointXYZRGBAtoXYZHSV(), pcl::PointCloud< PointT >::push_back(), and pcl::PointCloud< PointT >::width.
|
inline |
Convert a XYZRGB point cloud to a XYZHSV.
[in] | in | the input XYZRGB point cloud |
[out] | out | the output XYZHSV point cloud |
Definition at line 355 of file point_types_conversion.h.
References pcl::PointCloud< PointT >::height, PointXYZRGBtoXYZHSV(), pcl::PointCloud< PointT >::push_back(), and pcl::PointCloud< PointT >::width.
|
inline |
Convert a XYZRGB point cloud to a XYZI.
[in] | in | the input XYZRGB point cloud |
[out] | out | the output XYZI point cloud |
Definition at line 409 of file point_types_conversion.h.
References pcl::PointCloud< PointT >::height, PointXYZRGBtoXYZI(), pcl::PointCloud< PointT >::push_back(), and pcl::PointCloud< PointT >::width.
Convert a RGB point type to a I.
Definition at line 72 of file point_types_conversion.h.
Referenced by PointCloudRGBtoI().
|
inline |
Convert a RGB point type to a I.
Definition at line 95 of file point_types_conversion.h.
|
inline |
Convert a RGB point type to a I.
Definition at line 83 of file point_types_conversion.h.
|
inline |
Definition at line 233 of file point_types_conversion.h.
References pcl::_PointXYZHSV::h, pcl::_PointXYZHSV::s, and pcl::_PointXYZHSV::v.
Referenced by PointCloudXYZHSVtoXYZRGB().
|
inline |
Convert a XYZRGBA point type to a XYZHSV.
[in] | in | the input XYZRGBA point |
[out] | out | the output XYZHSV point |
Definition at line 196 of file point_types_conversion.h.
References pcl::_PointXYZHSV::h, pcl::_PointXYZHSV::s, and pcl::_PointXYZHSV::v.
Referenced by PointCloudXYZRGBAtoXYZHSV().
|
inline |
Convert a XYZRGB point type to a XYZHSV.
[in] | in | the input XYZRGB point |
[out] | out | the output XYZHSV point |
Definition at line 107 of file point_types_conversion.h.
References pcl::_PointXYZHSV::h, pcl::_PointXYZHSV::s, and pcl::_PointXYZHSV::v.
Referenced by PointCloudXYZRGBtoXYZHSV(), and seededHueSegmentation().
|
inline |
Convert a XYZRGB point type to a XYZI.
[in] | in | the input XYZRGB point |
[out] | out | the output XYZI point |
Definition at line 60 of file point_types_conversion.h.
References pcl::_PointXYZI::intensity.
Referenced by PointCloudXYZRGBtoXYZI().
|
inline |
Convert a XYZRGB-based point type to a XYZLAB.
[in] | in | the input XYZRGB(XYZRGBA, XYZRGBL, etc.) point |
[out] | out | the output XYZLAB point |
Definition at line 145 of file point_types_conversion.h.
References pcl::_PointXYZLAB::a, B, pcl::_PointXYZLAB::b, and pcl::_PointXYZLAB::L.
|
inline |
Project a point on a planar model given by a set of normalized coefficients.
[in] | p | the input point to project |
[in] | model_coefficients | the coefficients of the plane (a, b, c, d) that satisfy ax+by+cz+d=0 |
[out] | q | the resultant projected point |
Definition at line 62 of file sac_model_plane.h.
Referenced by pcl::search::OrganizedNeighbor< PointT >::estimateProjectionMatrix().
int pcl::radius_search | ( | const FlannIndex & | index, |
const Query & | query, | ||
Indices & | indices, | ||
Distances & | dists, | ||
float | radius, | ||
const SearchParams & | params | ||
) |
Compatibility template function to allow use of various types of indices with FLANN.
Template is used for all params to not constrain any FLANN side capability
[in,out] | index | A index searcher, of type ::flann::Index<Dist> or similar, where Dist is a template for computing distance between 2 points |
[in] | query | A ::flann::Matrix<float> or compatible matrix representation of the query point |
[out] | indices | Indices found in radius |
[out] | dists | Computed distance matrix |
[in] | radius | Threshold for consideration |
[in] | params | Any parameters to pass to the radius_search call |
Definition at line 360 of file kdtree_flann.hpp.
Referenced by pcl::KdTreeFLANN< PointT, Dist >::radiusSearch(), and pcl::search::FlannSearch< PointT, FlannDistance >::radiusSearch().
void pcl::read | ( | std::istream & | stream, |
Type & | value | ||
) |
Function for reading data from a stream.
Definition at line 46 of file region_xy.h.
Referenced by pcl::RegionXY::deserialize(), pcl::DenseQuantizedSingleModTemplate::deserialize(), pcl::DenseQuantizedMultiModTemplate::deserialize(), pcl::QuantizedMultiModFeature::deserialize(), pcl::SparseQuantizedMultiModTemplate::deserialize(), pcl::poisson::SparseMatrix< T >::read(), pcl::poisson::Vector< T >::read(), pcl::FileReader::read(), pcl::PLYReader::read(), pcl::IFSReader::read(), pcl::OBJReader::read(), pcl::PCDReader::read(), and read().
void pcl::read | ( | std::istream & | stream, |
Type * | value, | ||
int | nr_values | ||
) |
Function for reading data arrays from a stream.
Definition at line 53 of file region_xy.h.
References read().
|
inlinenoexcept |
Returns a Look-Up Table useful in converting RGB to sRGB.
T | floating point type with resultant value |
bits | depth of RGB |
|
inline |
Set the value at a specified field in a point.
[out] | pt | the point to set the value to |
[in] | field_offset | the offset of the field |
[in] | value | the value to set |
Definition at line 237 of file type_traits.h.
void pcl::split | ( | SequenceSequenceT & | result, |
std::string const & | in, | ||
const char *const | delimiters | ||
) |
Lightweight tokenization function This function can be used as a boost::split substitute.
When benchmarked against boost, this function will create much less allocations and hence it is much better suited for quick line tokenization.
Cool thing is this function will work with SequenceSequenceT = std::vector<std::string> and std::vector<std::string_view>
|
inline |
Definition at line 51 of file grabcut_segmentation.hpp.
References pcl::segmentation::grabcut::Color::b, pcl::segmentation::grabcut::Color::g, and pcl::segmentation::grabcut::Color::r.
|
inline |
Calculate the squared euclidean distance between the two given points.
[in] | p1 | the first point |
[in] | p2 | the second point |
Definition at line 182 of file distances.h.
Referenced by pcl::filters::Pyramid< PointT >::compute(), pcl::GrabCut< PointT >::computeBetaNonOrganized(), pcl::GrabCut< PointT >::computeBetaOrganized(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, pcl::Normal, float >::determineBaseMatches(), euclideanDistance(), pcl::RangeImage::getEuclideanDistanceSquared(), pcl::RangeImage::getImpactAngle(), pcl::RangeImageBorderExtractor::getNeighborDistanceChangeScore(), pcl::RangeImage::getSquaredDistanceOfNthNeighbor(), pcl::RangeImage::getSurfaceInformation(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::linkMatchWithBase(), pcl::SurfelSmoothing< PointT, PointNT >::smoothCloudIteration(), and pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateMatch().
Calculate the squared euclidean distance between the two given points.
[in] | p1 | the first point |
[in] | p2 | the second point |
Definition at line 193 of file distances.h.
References pcl::PointXY::x, and pcl::PointXY::y.
bool pcl::threePlanesIntersection | ( | const Eigen::Matrix< Scalar, 4, 1 > & | plane_a, |
const Eigen::Matrix< Scalar, 4, 1 > & | plane_b, | ||
const Eigen::Matrix< Scalar, 4, 1 > & | plane_c, | ||
Eigen::Matrix< Scalar, 3, 1 > & | intersection_point, | ||
double | determinant_tolerance = 1e-6 |
||
) |
Determine the point of intersection of three non-parallel planes by solving the equations.
[in] | plane_a | are the coefficients of the first plane in the form ax + by + cz + d = 0 |
[in] | plane_b | are the coefficients of the second plane |
[in] | plane_c | are the coefficients of the third plane |
[in] | determinant_tolerance | is a limit to determine whether planes are parallel or not |
[out] | intersection_point | the three coordinates x, y, z of the intersection point |
Definition at line 127 of file intersections.hpp.
|
inline |
Definition at line 144 of file intersections.h.
|
inline |
Definition at line 133 of file intersections.h.
void pcl::toPCLPointCloud2 | ( | const CloudT & | cloud, |
pcl::PCLImage & | msg | ||
) |
Copy the RGB fields of a PointCloud into pcl::PCLImage format.
[in] | cloud | the point cloud message |
[out] | msg | the resultant pcl::PCLImage CloudT cloud type, CloudT should be akin to pcl::PointCloud<pcl::PointXYZRGBA> |
Definition at line 442 of file conversions.h.
References pcl::PCLImage::data, pcl::PCLImage::encoding, pcl::PCLImage::header, pcl::PCLImage::height, pcl::PCLImage::step, and pcl::PCLImage::width.
|
inline |
Copy the RGB fields of a PCLPointCloud2 msg into pcl::PCLImage format.
cloud | the point cloud message |
msg | the resultant pcl::PCLImage will throw std::runtime_error if there is a problem |
Definition at line 476 of file conversions.h.
References pcl::PCLImage::data, pcl::PCLPointCloud2::data, pcl::geometry::distance(), pcl::PCLImage::encoding, pcl::PCLPointCloud2::fields, pcl::PCLImage::header, pcl::PCLPointCloud2::header, pcl::PCLImage::height, pcl::PCLPointCloud2::height, pcl::PCLPointCloud2::point_step, pcl::PCLImage::step, pcl::PCLImage::width, and pcl::PCLPointCloud2::width.
void pcl::toPCLPointCloud2 | ( | const pcl::PointCloud< PointT > & | cloud, |
pcl::PCLPointCloud2 & | msg | ||
) |
Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
[in] | cloud | the input pcl::PointCloud<T> |
[out] | msg | the resultant PCLPointCloud2 binary blob |
Definition at line 430 of file conversions.h.
References toPCLPointCloud2().
void pcl::toPCLPointCloud2 | ( | const pcl::PointCloud< PointT > & | cloud, |
pcl::PCLPointCloud2 & | msg, | ||
bool | padding | ||
) |
Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
[in] | cloud | the input pcl::PointCloud<T> |
[out] | msg | the resultant PCLPointCloud2 binary blob |
[in] | padding | Many point types have padding to ensure alignment and SIMD compatibility. Setting this to true will copy the padding to the PCLPointCloud2 (the default in older PCL versions). Setting this to false will make the data blob in PCLPointCloud2 smaller, while still keeping all information (useful e.g. when sending msg over network or storing it). The amount of padding depends on the point type, and can in some cases be up to 50 percent. |
Definition at line 372 of file conversions.h.
References pcl::PCLPointCloud2::data, pcl::PointCloud< PointT >::data(), pcl::PCLPointCloud2::fields, pcl::PCLPointCloud2::header, pcl::PointCloud< PointT >::header, pcl::PCLPointCloud2::height, pcl::PointCloud< PointT >::height, pcl::PCLPointCloud2::is_dense, pcl::PointCloud< PointT >::is_dense, pcl::PCLPointCloud2::point_step, pcl::PCLPointCloud2::row_step, pcl::PointCloud< PointT >::size(), pcl::PCLPointCloud2::width, and pcl::PointCloud< PointT >::width.
Referenced by pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::computeTransformation(), pcl::JointIterativeClosestPoint< PointSource, PointTarget, Scalar >::computeTransformation(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::convertTrianglesToMesh(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::getMeshesFromTSDFVector(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::MarchingCubes< PointNT >::performReconstruction(), pcl::Poisson< PointNT >::performReconstruction(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction(), pcl::SurfaceReconstruction< PointInT >::reconstruct(), pcl::geometry::toFaceVertexMesh(), toPCLPointCloud2(), pcl::PLYWriter::write(), and pcl::FileWriter::write().
bool pcl::transformBetween2CoordinateSystems | ( | const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > | from_line_x, |
const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > | from_line_y, | ||
const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > | to_line_x, | ||
const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > | to_line_y, | ||
Eigen::Transform< Scalar, 3, Eigen::Affine > & | transformation | ||
) |
Compute the transformation between two coordinate systems.
[in] | from_line_x | X axis from the origin coordinate system |
[in] | from_line_y | Y axis from the origin coordinate system |
[in] | to_line_x | X axis from the destination coordinate system |
[in] | to_line_y | Y axis from the destination coordinate system |
[out] | transformation | the transformation matrix to fill |
Line must be filled in this form:
line[0-2] = Coordinate system origin coordinates
line[3-5] = Direction vector (norm doesn't matter)
Definition at line 864 of file eigen.hpp.
References checkCoordinateSystem().
bool pcl::transformLine | ( | const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > & | line_in, |
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > & | line_out, | ||
const Eigen::Transform< Scalar, 3, Eigen::Affine > & | transformation | ||
) |
Transform a line using an affine matrix.
[in] | line_in | the line to be transformed |
[out] | line_out | the transformed line |
[in] | transformation | the transformation matrix |
Lines must be filled in this form:
line[0-2] = Origin coordinates of the vector
line[3-5] = Direction vector
line_in
= line_out
Definition at line 746 of file eigen.hpp.
References transformPoint(), and transformVector().
void pcl::transformPlane | ( | const Eigen::Matrix< Scalar, 4, 1 > & | plane_in, |
Eigen::Matrix< Scalar, 4, 1 > & | plane_out, | ||
const Eigen::Transform< Scalar, 3, Eigen::Affine > & | transformation | ||
) |
Transform plane vectors using an affine matrix.
[in] | plane_in | the plane coefficients to be transformed |
[out] | plane_out | the transformed plane coefficients to fill |
[in] | transformation | the transformation matrix |
The plane vectors are filled in the form ax+by+cz+d=0 Can be used with non Hessian form planes coefficients Can be used with plane_in
= plane_out
Definition at line 768 of file eigen.hpp.
Referenced by transformPlane().
void pcl::transformPlane | ( | const pcl::ModelCoefficients::ConstPtr | plane_in, |
pcl::ModelCoefficients::Ptr | plane_out, | ||
const Eigen::Transform< Scalar, 3, Eigen::Affine > & | transformation | ||
) |
Transform plane vectors using an affine matrix.
[in] | plane_in | the plane coefficients to be transformed |
[out] | plane_out | the transformed plane coefficients to fill |
[in] | transformation | the transformation matrix |
The plane vectors are filled in the form ax+by+cz+d=0 Can be used with non Hessian form planes coefficients Can be used with plane_in
= plane_out
Definition at line 785 of file eigen.hpp.
References transformPlane().
|
inline |
Transform a point using an affine matrix.
[in] | point_in | the vector to be transformed |
[out] | point_out | the transformed vector |
[in] | transformation | the transformation matrix |
point_in
= point_out
Definition at line 389 of file eigen.h.
Referenced by transformLine().
|
inline |
Definition at line 464 of file transforms.h.
void pcl::transformPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const Indices & | indices, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Affine3f & | transform, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 96 of file transforms.h.
void pcl::transformPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const Indices & | indices, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Matrix4f & | transform, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 261 of file transforms.h.
void pcl::transformPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const pcl::PointIndices & | indices, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Affine3f & | transform, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 125 of file transforms.h.
References pcl::PointIndices::indices.
void pcl::transformPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const pcl::PointIndices & | indices, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Matrix4f & | transform, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 290 of file transforms.h.
void pcl::transformPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Affine3f & | transform, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 68 of file transforms.h.
void pcl::transformPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Matrix4f & | transform, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 236 of file transforms.h.
|
inline |
Definition at line 403 of file transforms.h.
void pcl::transformPointCloudWithNormals | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const Indices & | indices, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Affine3f & | transform, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 181 of file transforms.h.
void pcl::transformPointCloudWithNormals | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const Indices & | indices, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Matrix4f & | transform, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 345 of file transforms.h.
void pcl::transformPointCloudWithNormals | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const Indices & | indices, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Transform< Scalar, 3, Eigen::Affine > & | transform, | ||
bool | copy_all_fields = true |
||
) |
Transform a point cloud and rotate its normals using an Eigen transform.
[in] | cloud_in | the input point cloud |
[in] | indices | the set of point indices to use from the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | an affine transformation (typically a rigid transformation) |
[in] | copy_all_fields | flag that controls whether the contents of the fields (other than x, y, z, normal_x, normal_y, normal_z) should be copied into the new transformed cloud |
Definition at line 171 of file transforms.h.
void pcl::transformPointCloudWithNormals | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const pcl::PointIndices & | indices, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Affine3f & | transform, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 211 of file transforms.h.
References pcl::PointIndices::indices.
void pcl::transformPointCloudWithNormals | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const pcl::PointIndices & | indices, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Matrix4f & | transform, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 377 of file transforms.h.
References pcl::PointIndices::indices.
void pcl::transformPointCloudWithNormals | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const pcl::PointIndices & | indices, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Transform< Scalar, 3, Eigen::Affine > & | transform, | ||
bool | copy_all_fields = true |
||
) |
Transform a point cloud and rotate its normals using an Eigen transform.
[in] | cloud_in | the input point cloud |
[in] | indices | the set of point indices to use from the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | an affine transformation (typically a rigid transformation) |
[in] | copy_all_fields | flag that controls whether the contents of the fields (other than x, y, z, normal_x, normal_y, normal_z) should be copied into the new transformed cloud |
Definition at line 200 of file transforms.h.
References pcl::PointIndices::indices.
void pcl::transformPointCloudWithNormals | ( | const pcl::PointCloud< PointT > & | cloud_in, |
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Affine3f & | transform, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 153 of file transforms.h.
void pcl::transformPointCloudWithNormals | ( | const pcl::PointCloud< PointT > & | cloud_in, |
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Matrix4f & | transform, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 317 of file transforms.h.
void pcl::transformPointCloudWithNormals | ( | const pcl::PointCloud< PointT > & | cloud_in, |
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Transform< Scalar, 3, Eigen::Affine > & | transform, | ||
bool | copy_all_fields = true |
||
) |
Transform a point cloud and rotate its normals using an Eigen transform.
[in] | cloud_in | the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | an affine transformation (typically a rigid transformation) |
[in] | copy_all_fields | flag that controls whether the contents of the fields (other than x, y, z, normal_x, normal_y, normal_z) should be copied into the new transformed cloud |
Definition at line 144 of file transforms.h.
void pcl::transformPointCloudWithNormals | ( | const pcl::PointCloud< PointT > & | cloud_in, |
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::Vector3f & | offset, | ||
const Eigen::Quaternionf & | rotation, | ||
bool | copy_all_fields = true |
||
) |
Definition at line 430 of file transforms.h.
|
inline |
Definition at line 481 of file transforms.h.
|
inline |
Transform a vector using an affine matrix.
[in] | vector_in | the vector to be transformed |
[out] | vector_out | the transformed vector |
[in] | transformation | the transformation matrix |
vector_in
= vector_out
Definition at line 406 of file eigen.h.
Referenced by transformLine().
Eigen::internal::umeyama_transform_matrix_type< Derived, OtherDerived >::type pcl::umeyama | ( | const Eigen::MatrixBase< Derived > & | src, |
const Eigen::MatrixBase< OtherDerived > & | dst, | ||
bool | with_scaling = false |
||
) |
Returns the transformation between two point sets.
The algorithm is based on: "Least-squares estimation of transformation parameters between two point patterns", Shinji Umeyama, PAMI 1991, DOI: 10.1109/34.88573
It estimates parameters and
such that
is minimized.
The algorithm is based on the analysis of the covariance matrix of the input point sets
and
where
is corresponding to the dimension (which is typically small). The analysis is involving the SVD having a complexity of
though the actual computational effort lies in the covariance matrix computation which has an asymptotic lower bound of
when the input point sets have dimension
.
[in] | src | Source points ![]() |
[in] | dst | Destination points ![]() |
[in] | with_scaling | Sets ![]() false is passed. (default: false) |
Definition at line 670 of file eigen.hpp.
Referenced by pcl::SampleConsensusModelRegistration< PointT >::estimateRigidTransformationSVD().
void pcl::write | ( | std::ostream & | stream, |
Type * | value, | ||
int | nr_values | ||
) |
Function for writing data arrays to a stream.
Definition at line 70 of file region_xy.h.
References write().
void pcl::write | ( | std::ostream & | stream, |
Type | value | ||
) |
Function for writing data to a stream.
Definition at line 63 of file region_xy.h.
Referenced by pcl::DenseQuantizedSingleModTemplate::serialize(), pcl::DenseQuantizedMultiModTemplate::serialize(), pcl::RegionXY::serialize(), pcl::QuantizedMultiModFeature::serialize(), pcl::SparseQuantizedMultiModTemplate::serialize(), pcl::io::LZFImageWriter::write(), pcl::poisson::SparseMatrix< T >::write(), pcl::poisson::Vector< T >::write(), pcl::PLYWriter::write(), pcl::FileWriter::write(), pcl::PCDWriter::write(), pcl::IFSWriter::write(), and write().
|
inlinenoexcept |
Returns a Look-Up Table useful in converting scaled CIE XYZ into CIE L*a*b*.
The function assumes that the XYZ values are
T | floating point type with resultant value |
discretizations | number of levels for the LUT |
const unsigned int pcl::edgeTable[256] |
Definition at line 59 of file marching_cubes.h.
Referenced by pcl::MarchingCubes< PointNT >::createSurface().
const int pcl::I_SHIFT_EDGE[3][2] |
Definition at line 60 of file grid_projection.h.
Referenced by pcl::GridProjection< PointNT >::createSurfaceForCell().
const int pcl::I_SHIFT_EP[12][2] |
The 12 edges of a cell.
Definition at line 50 of file grid_projection.h.
const int pcl::I_SHIFT_PT[4] |
Definition at line 56 of file grid_projection.h.
Referenced by pcl::GridProjection< PointNT >::createSurfaceForCell().
|
constexpr |
Definition at line 285 of file type_traits.h.
|
constexpr |
Definition at line 280 of file type_traits.h.
|
constexpr |
Definition at line 46 of file method_types.h.
Referenced by pcl::SACSegmentation< PointT >::initSAC().
|
constexpr |
Definition at line 50 of file method_types.h.
Referenced by pcl::SACSegmentation< PointT >::initSAC().
|
constexpr |
Definition at line 47 of file method_types.h.
Referenced by pcl::SACSegmentation< PointT >::initSAC().
|
constexpr |
Definition at line 51 of file method_types.h.
Referenced by pcl::SACSegmentation< PointT >::initSAC().
|
constexpr |
Definition at line 45 of file method_types.h.
Referenced by pcl::SACSegmentation< PointT >::initSAC().
|
constexpr |
Definition at line 49 of file method_types.h.
Referenced by pcl::SACSegmentation< PointT >::initSAC().
|
constexpr |
Definition at line 48 of file method_types.h.
Referenced by pcl::SACSegmentation< PointT >::initSAC().
const int pcl::triTable[256][16] |
Definition at line 93 of file marching_cubes.h.
Referenced by pcl::MarchingCubes< PointNT >::createSurface().
Definition at line 62 of file pcl_base.h.
Referenced by pcl::visualization::PCLVisualizer::addCorrespondences(), pcl::visualization::PointPickingEvent::getPointIndices(), pcl::visualization::PointPickingEvent::getPoints(), pcl::GrabCut< PointT >::initGraph(), pcl::visualization::PointCloudGeometryHandlerCustom< PointT >::PointCloudGeometryHandlerCustom(), pcl::visualization::PointCloudGeometryHandlerSurfaceNormal< PointT >::PointCloudGeometryHandlerSurfaceNormal(), and pcl::visualization::PointCloudGeometryHandlerXYZ< PointT >::PointCloudGeometryHandlerXYZ().