Point Cloud Library (PCL)  1.14.0-dev
Classes | Files | Macros | Typedefs | Enumerations | Functions
Module common

Detailed Description

Overview

The pcl_common library contains the common data structures and methods used by the majority of PCL libraries. The core data structures include the PointCloud class and a multitude of point types that are used to represent points, surface normals, RGB color values, feature descriptors, etc. It also contains numerous functions for computing distances/norms, means and covariances, angular conversions, geometric transformations, and more.

Requirements

Classes

class  pcl::BivariatePolynomialT< real >
 This represents a bivariate polynomial and provides some functionality for it. More...
 
class  pcl::CentroidPoint< PointT >
 A generic class that computes the centroid of points fed to it. More...
 
struct  pcl::NdConcatenateFunctor< PointInT, PointOutT >
 Helper functor structure for concatenate. More...
 
class  pcl::FeatureHistogram
 Type for histograms for computing mean and variance of some floats. More...
 
class  pcl::GaussianKernel
 Class GaussianKernel assembles all the method for computing, convolving, smoothing, gradients computing an image using a gaussian kernel. More...
 
class  pcl::PCA< PointT >
 Principal Component analysis (PCA) class. More...
 
class  pcl::PiecewiseLinearFunction
 This provides functionalities to efficiently return values for piecewise linear function. More...
 
class  pcl::PolynomialCalculationsT< real >
 This provides some functionality for polynomials, like finding roots or approximating bivariate polynomials. More...
 
class  pcl::PosesFromMatches
 calculate 3D transformation based on point correspondences More...
 
class  pcl::StopWatch
 Simple stopwatch. More...
 
class  pcl::ScopeTime
 Class to measure the time spent in a scope. More...
 
class  pcl::EventFrequency
 A helper class to measure frequency of a certain event. More...
 
class  pcl::TimeTrigger
 Timer class that invokes registered callback methods periodically. More...
 
class  pcl::TransformationFromCorrespondences
 Calculates a transformation based on corresponding 3D points. More...
 
class  pcl::VectorAverage< real, dimension >
 Calculates the weighted average and the covariance matrix. More...
 
struct  pcl::Correspondence
 Correspondence represents a match between two entities (e.g., points, descriptors, etc). More...
 
struct  pcl::PointCorrespondence3D
 Representation of a (possible) correspondence between two 3D points in two different coordinate frames (e.g. More...
 
struct  pcl::PointCorrespondence6D
 Representation of a (possible) correspondence between two points (e.g. More...
 
struct  pcl::PointXYZ
 A point structure representing Euclidean xyz coordinates. More...
 
struct  pcl::Intensity
 A point structure representing the grayscale intensity in single-channel images. More...
 
struct  pcl::Intensity8u
 A point structure representing the grayscale intensity in single-channel images. More...
 
struct  pcl::Intensity32u
 A point structure representing the grayscale intensity in single-channel images. More...
 
struct  pcl::_PointXYZI
 A point structure representing Euclidean xyz coordinates, and the intensity value. More...
 
struct  pcl::PointXYZRGBA
 A point structure representing Euclidean xyz coordinates, and the RGBA color. More...
 
struct  pcl::PointXYZRGB
 A point structure representing Euclidean xyz coordinates, and the RGB color. More...
 
struct  pcl::PointXYZLAB
 A point structure representing Euclidean xyz coordinates, and the CIELAB color. More...
 
struct  pcl::PointXY
 A 2D point structure representing Euclidean xy coordinates. More...
 
struct  pcl::PointUV
 A 2D point structure representing pixel image coordinates. More...
 
struct  pcl::InterestPoint
 A point structure representing an interest point with Euclidean xyz coordinates, and an interest value. More...
 
struct  pcl::Normal
 A point structure representing normal coordinates and the surface curvature estimate. More...
 
struct  pcl::Axis
 A point structure representing an Axis using its normal coordinates. More...
 
struct  pcl::PointNormal
 A point structure representing Euclidean xyz coordinates, together with normal coordinates and the surface curvature estimate. More...
 
struct  pcl::PointXYZRGBNormal
 A point structure representing Euclidean xyz coordinates, and the RGB color, together with normal coordinates and the surface curvature estimate. More...
 
struct  pcl::PointXYZINormal
 A point structure representing Euclidean xyz coordinates, intensity, together with normal coordinates and the surface curvature estimate. More...
 
struct  pcl::PointXYZLNormal
 A point structure representing Euclidean xyz coordinates, a label, together with normal coordinates and the surface curvature estimate. More...
 
struct  pcl::PointWithRange
 A point structure representing Euclidean xyz coordinates, padded with an extra range float. More...
 
struct  pcl::PointWithViewpoint
 A point structure representing Euclidean xyz coordinates together with the viewpoint from which it was seen. More...
 
struct  pcl::MomentInvariants
 A point structure representing the three moment invariants. More...
 
struct  pcl::PrincipalRadiiRSD
 A point structure representing the minimum and maximum surface radii (in meters) computed using RSD. More...
 
struct  pcl::Boundary
 A point structure representing a description of whether a point is lying on a surface boundary or not. More...
 
struct  pcl::PrincipalCurvatures
 A point structure representing the principal curvatures and their magnitudes. More...
 
struct  pcl::PFHSignature125
 A point structure representing the Point Feature Histogram (PFH). More...
 
struct  pcl::PFHRGBSignature250
 A point structure representing the Point Feature Histogram with colors (PFHRGB). More...
 
struct  pcl::PPFSignature
 A point structure for storing the Point Pair Feature (PPF) values. More...
 
struct  pcl::CPPFSignature
 A point structure for storing the Point Pair Feature (CPPF) values. More...
 
struct  pcl::PPFRGBSignature
 A point structure for storing the Point Pair Color Feature (PPFRGB) values. More...
 
struct  pcl::NormalBasedSignature12
 A point structure representing the Normal Based Signature for a feature matrix of 4-by-3. More...
 
struct  pcl::ShapeContext1980
 A point structure representing a Shape Context. More...
 
struct  pcl::UniqueShapeContext1960
 A point structure representing a Unique Shape Context. More...
 
struct  pcl::SHOT352
 A point structure representing the generic Signature of Histograms of OrienTations (SHOT) - shape only. More...
 
struct  pcl::SHOT1344
 A point structure representing the generic Signature of Histograms of OrienTations (SHOT) - shape+color. More...
 
struct  pcl::_ReferenceFrame
 A structure representing the Local Reference Frame of a point. More...
 
struct  pcl::FPFHSignature33
 A point structure representing the Fast Point Feature Histogram (FPFH). More...
 
struct  pcl::VFHSignature308
 A point structure representing the Viewpoint Feature Histogram (VFH). More...
 
struct  pcl::GRSDSignature21
 A point structure representing the Global Radius-based Surface Descriptor (GRSD). More...
 
struct  pcl::BRISKSignature512
 A point structure representing the Binary Robust Invariant Scalable Keypoints (BRISK). More...
 
struct  pcl::ESFSignature640
 A point structure representing the Ensemble of Shape Functions (ESF). More...
 
struct  pcl::GASDSignature512
 A point structure representing the Globally Aligned Spatial Distribution (GASD) shape descriptor. More...
 
struct  pcl::GASDSignature984
 A point structure representing the Globally Aligned Spatial Distribution (GASD) shape and color descriptor. More...
 
struct  pcl::GASDSignature7992
 A point structure representing the Globally Aligned Spatial Distribution (GASD) shape and color descriptor. More...
 
struct  pcl::GFPFHSignature16
 A point structure representing the GFPFH descriptor with 16 bins. More...
 
struct  pcl::Narf36
 A point structure representing the Narf descriptor. More...
 
struct  pcl::BorderDescription
 A structure to store if a point in a range image lies on a border between an obstacle and the background. More...
 
struct  pcl::IntensityGradient
 A point structure representing the intensity gradient of an XYZI point cloud. More...
 
struct  pcl::Histogram< N >
 A point structure representing an N-D histogram. More...
 
struct  pcl::PointWithScale
 A point structure representing a 3-D position and scale. More...
 
struct  pcl::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  pcl::PointDEM
 A point structure representing Digital Elevation Map. More...
 
class  pcl::PCLBase< PointT >
 PCL base class. More...
 
class  pcl::cuda::ScopeTimeCPU
 Class to measure the time spent in a scope. More...
 
struct  pcl::GradientXY
 A point structure representing Euclidean xyz coordinates, and the intensity value. More...
 

Files

file  angles.h
 Define standard C methods to do angle calculations.
 
file  centroid.h
 Define methods for centroid estimation and covariance matrix calculus.
 
file  common.h
 Define standard C methods and C++ classes that are common to all methods.
 
file  distances.h
 Define standard C methods to do distance calculations.
 
file  file_io.h
 Define some helper functions for reading and writing files.
 
file  random.h
 CloudGenerator class generates a point cloud using some random number generator.
 
file  geometry.h
 Defines some geometrical functions and utility functions.
 
file  intersections.h
 Define line with line intersection functions.
 
file  norms.h
 Define standard C methods to calculate different norms.
 
file  geometry.h
 Defines some geometrical functions and utility functions.
 
file  time.h
 Define methods for measuring time spent in code blocks.
 
file  memory.h
 Defines functions, macros and traits for allocating and using memory.
 
file  pcl_macros.h
 Defines all the PCL and non-PCL macros used.
 
file  point_types.h
 Defines all the PCL implemented PointT point type structures.
 
file  types.h
 Defines basic non-point types used by PCL.
 

Macros

#define PCL_MAKE_ALIGNED_OPERATOR_NEW
 Macro to signal a class requires a custom allocator. More...
 
#define PCL_FALLTHROUGH
 Macro to add a no-op or a fallthrough attribute based on compiler feature. More...
 

Typedefs

using pcl::BorderTraits = std::bitset< 32 >
 Data type to store extended information about a transition from foreground to backgroundSpecification of the fields for BorderDescription::traits. More...
 

Enumerations

enum  pcl::NormType {
  pcl::L1 , pcl::L2_SQR , pcl::L2 , pcl::LINF ,
  pcl::JM , pcl::B , pcl::SUBLINEAR , pcl::CS ,
  pcl::DIV , pcl::PF , pcl::K , pcl::KL ,
  pcl::HIK
}
 Enum that defines all the types of norms available. More...
 
enum  pcl::BorderTrait {
  pcl::BORDER_TRAIT__OBSTACLE_BORDER , pcl::BORDER_TRAIT__SHADOW_BORDER , pcl::BORDER_TRAIT__VEIL_POINT , pcl::BORDER_TRAIT__SHADOW_BORDER_TOP ,
  pcl::BORDER_TRAIT__SHADOW_BORDER_RIGHT , pcl::BORDER_TRAIT__SHADOW_BORDER_BOTTOM , pcl::BORDER_TRAIT__SHADOW_BORDER_LEFT , pcl::BORDER_TRAIT__OBSTACLE_BORDER_TOP ,
  pcl::BORDER_TRAIT__OBSTACLE_BORDER_RIGHT , pcl::BORDER_TRAIT__OBSTACLE_BORDER_BOTTOM , pcl::BORDER_TRAIT__OBSTACLE_BORDER_LEFT , pcl::BORDER_TRAIT__VEIL_POINT_TOP ,
  pcl::BORDER_TRAIT__VEIL_POINT_RIGHT , pcl::BORDER_TRAIT__VEIL_POINT_BOTTOM , pcl::BORDER_TRAIT__VEIL_POINT_LEFT
}
 Specification of the fields for BorderDescription::traits. More...
 

Functions

float pcl::rad2deg (float alpha)
 Convert an angle from radians to degrees. More...
 
float pcl::deg2rad (float alpha)
 Convert an angle from degrees to radians. More...
 
double pcl::rad2deg (double alpha)
 Convert an angle from radians to degrees. More...
 
double pcl::deg2rad (double alpha)
 Convert an angle from degrees to radians. More...
 
float pcl::normAngle (float alpha)
 Normalize an angle to (-PI, PI]. More...
 
template<typename PointT , typename Scalar >
unsigned int pcl::compute3DCentroid (ConstCloudIterator< PointT > &cloud_iterator, Eigen::Matrix< Scalar, 4, 1 > &centroid)
 Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector. More...
 
template<typename PointT , typename Scalar >
unsigned int pcl::compute3DCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix< Scalar, 4, 1 > &centroid)
 Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector. More...
 
template<typename PointT , typename Scalar >
unsigned int pcl::compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix< Scalar, 4, 1 > &centroid)
 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 , typename Scalar >
unsigned int pcl::compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix< Scalar, 4, 1 > &centroid)
 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 , typename Scalar >
unsigned int pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Eigen::Matrix< Scalar, 4, 1 > &centroid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix)
 Compute the 3x3 covariance matrix of a given set of points. More...
 
template<typename PointT , typename Scalar >
unsigned int pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const Eigen::Matrix< Scalar, 4, 1 > &centroid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix)
 Compute normalized the 3x3 covariance matrix of a given set of points. More...
 
template<typename PointT , typename Scalar >
unsigned int pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Indices &indices, const Eigen::Matrix< Scalar, 4, 1 > &centroid, 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 , typename Scalar >
unsigned int pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Matrix< Scalar, 4, 1 > &centroid, 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 , typename Scalar >
unsigned int pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const Indices &indices, const Eigen::Matrix< Scalar, 4, 1 > &centroid, 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 , typename Scalar >
unsigned int pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Matrix< Scalar, 4, 1 > &centroid, 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 , typename Scalar >
unsigned int pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix, Eigen::Matrix< Scalar, 4, 1 > &centroid)
 Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. More...
 
template<typename PointT , typename Scalar >
unsigned int pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix, Eigen::Matrix< Scalar, 4, 1 > &centroid)
 Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. More...
 
template<typename PointT , typename Scalar >
unsigned int pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix, Eigen::Matrix< Scalar, 4, 1 > &centroid)
 Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. More...
 
template<typename PointT , typename Scalar >
unsigned int pcl::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 , typename Scalar >
unsigned int pcl::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 , typename Scalar >
unsigned int pcl::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 , typename Scalar >
unsigned int pcl::computeCentroidAndOBB (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix< Scalar, 3, 1 > &centroid, 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 pcl::computeCentroidAndOBB (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix< Scalar, 3, 1 > &centroid, 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 pcl::demeanPointCloud (ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Matrix< Scalar, 4, 1 > &centroid, 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 , typename Scalar >
void pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Eigen::Matrix< Scalar, 4, 1 > &centroid, pcl::PointCloud< PointT > &cloud_out)
 Subtract a centroid from a point cloud and return the de-meaned representation. More...
 
template<typename PointT , typename Scalar >
void pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, const Eigen::Matrix< Scalar, 4, 1 > &centroid, pcl::PointCloud< PointT > &cloud_out)
 Subtract a centroid from a point cloud and return the de-meaned representation. More...
 
template<typename PointT , typename Scalar >
void pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, const Eigen::Matrix< Scalar, 4, 1 > &centroid, pcl::PointCloud< PointT > &cloud_out)
 Subtract a centroid from a point cloud and return the de-meaned representation. More...
 
template<typename PointT , typename Scalar >
void pcl::demeanPointCloud (ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Matrix< Scalar, 4, 1 > &centroid, 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 , typename Scalar >
void pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Eigen::Matrix< Scalar, 4, 1 > &centroid, 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 , typename Scalar >
void pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, const Eigen::Matrix< Scalar, 4, 1 > &centroid, 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 , typename Scalar >
void pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, const Eigen::Matrix< Scalar, 4, 1 > &centroid, 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 , typename Scalar >
void pcl::computeNDCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &centroid)
 General, all purpose nD centroid estimation for a set of points using their indices. More...
 
template<typename PointT , typename Scalar >
void pcl::computeNDCentroid (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &centroid)
 General, all purpose nD centroid estimation for a set of points using their indices. More...
 
template<typename PointT , typename Scalar >
void pcl::computeNDCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &centroid)
 General, all purpose nD centroid estimation for a set of points using their indices. More...
 
template<typename PointInT , typename PointOutT >
std::size_t pcl::computeCentroid (const pcl::PointCloud< PointInT > &cloud, PointOutT &centroid)
 Compute the centroid of a set of points and return it as a point. More...
 
template<typename PointInT , typename PointOutT >
std::size_t pcl::computeCentroid (const pcl::PointCloud< PointInT > &cloud, const Indices &indices, PointOutT &centroid)
 Compute the centroid of a set of points and return it as a point. More...
 
double pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::calculatePolygonArea (const pcl::PointCloud< PointT > &polygon)
 Calculate the area of a polygon given a point cloud that defines the polygon. More...
 
PCL_EXPORTS void pcl::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 pcl::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 pcl::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 PointInT , typename PointOutT >
void pcl::copyPoint (const PointInT &point_in, PointOutT &point_out)
 Copy the fields of a source point into a target point. More...
 
PCL_EXPORTS void pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 Matrix , typename Vector >
void pcl::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 pcl::eigen22 (const Matrix &mat, Matrix &eigenvectors, Vector &eigenvalues)
 determine the smallest eigenvalue and its corresponding eigenvector More...
 
template<typename Matrix , typename Vector >
void pcl::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 pcl::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 pcl::eigen33 (const Matrix &mat, Vector &evals)
 determines the eigenvalues of the symmetric positive semi definite input matrix More...
 
template<typename Matrix , typename Vector >
void pcl::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 pcl::invert2x2 (const Matrix &matrix, Matrix &inverse)
 Calculate the inverse of a 2x2 matrix. More...
 
template<typename Matrix >
Matrix::Scalar pcl::invert3x3SymMatrix (const Matrix &matrix, Matrix &inverse)
 Calculate the inverse of a 3x3 symmetric matrix. More...
 
template<typename Matrix >
Matrix::Scalar pcl::invert3x3Matrix (const Matrix &matrix, Matrix &inverse)
 Calculate the inverse of a general 3x3 matrix. More...
 
template<typename Matrix >
Matrix::Scalar pcl::determinant3x3Matrix (const Matrix &matrix)
 Calculate the determinant of a 3x3 matrix. More...
 
void pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::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 pcl::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...
 
Eigen::Affine3f pcl::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 pcl::saveBinary (const Eigen::MatrixBase< Derived > &matrix, std::ostream &file)
 Write a matrix to an output stream. More...
 
template<typename Derived >
void pcl::loadBinary (Eigen::MatrixBase< Derived > const &matrix, std::istream &file)
 Read a matrix from an input stream. More...
 
bool pcl::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 pcl::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...
 
int pcl::getFieldIndex (const pcl::PCLPointCloud2 &cloud, const std::string &field_name)
 Get the index of a specified field (i.e., dimension/channel) More...
 
template<typename PointT >
int pcl::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 pcl::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 >
std::vector< pcl::PCLPointFieldpcl::getFields ()
 Get the list of available fields (i.e., dimension/channel) More...
 
template<typename PointT >
std::string pcl::getFieldsList (const pcl::PointCloud< PointT > &cloud)
 Get the list of all fields available in a given cloud. More...
 
std::string pcl::getFieldsList (const pcl::PCLPointCloud2 &cloud)
 Get the available point cloud fields as a space separated string. More...
 
int pcl::getFieldSize (const int datatype)
 Obtains the size of a specific field data type in bytes. More...
 
int pcl::getFieldType (const int size, char type)
 Obtains the type of the PCLPointField from a specific size and type. More...
 
char pcl::getFieldType (const int type)
 Obtains the type of the PCLPointField from a specific PCLPointField as a char. More...
 
template<typename PointT >
PCL_EXPORTS bool pcl::concatenate (const pcl::PointCloud< PointT > &cloud1, const pcl::PointCloud< PointT > &cloud2, pcl::PointCloud< PointT > &cloud_out)
 Concatenate two pcl::PointCloud<PointT> More...
 
PCL_EXPORTS bool pcl::concatenate (const pcl::PCLPointCloud2 &cloud1, const pcl::PCLPointCloud2 &cloud2, pcl::PCLPointCloud2 &cloud_out)
 Concatenate two pcl::PCLPointCloud2. More...
 
PCL_EXPORTS bool pcl::concatenate (const pcl::PolygonMesh &mesh1, const pcl::PolygonMesh &mesh2, pcl::PolygonMesh &mesh_out)
 Concatenate two pcl::PolygonMesh. More...
 
PCL_EXPORTS void pcl::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 pcl::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 pcl::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 PointT , typename IndicesVectorAllocator >
void pcl::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 PointT >
void pcl::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 PointT >
void pcl::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 pcl::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 PointInT , typename PointOutT , typename IndicesVectorAllocator >
void pcl::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 PointInT , typename PointOutT >
void pcl::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 PointInT , typename PointOutT >
void pcl::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 PointT >
void pcl::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 PointIn1T , typename PointIn2T , typename PointOutT >
void pcl::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...
 
PCL_EXPORTS bool pcl::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 pcl::getPointCloudAsEigen (const pcl::PCLPointCloud2 &in, Eigen::MatrixXf &out)
 Copy the XYZ dimensions of a pcl::PCLPointCloud2 into Eigen format. More...
 
PCL_EXPORTS bool pcl::getEigenAsPointCloud (Eigen::MatrixXf &in, pcl::PCLPointCloud2 &out)
 Copy the XYZ dimensions from an Eigen MatrixXf into a pcl::PCLPointCloud2 message. More...
 
template<std::size_t N>
void pcl::io::swapByte (char *bytes)
 swap bytes order of a char array of length N More...
 
template<typename FloatVectorT >
float pcl::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 pcl::L1_Norm (FloatVectorT A, FloatVectorT B, int dim)
 Compute the L1 norm of the vector between two points. More...
 
template<typename FloatVectorT >
float pcl::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 pcl::L2_Norm (FloatVectorT A, FloatVectorT B, int dim)
 Compute the L2 norm of the vector between two points. More...
 
template<typename FloatVectorT >
float pcl::Linf_Norm (FloatVectorT A, FloatVectorT B, int dim)
 Compute the L-infinity norm of the vector between two points. More...
 
template<typename FloatVectorT >
float pcl::JM_Norm (FloatVectorT A, FloatVectorT B, int dim)
 Compute the JM norm of the vector between two points. More...
 
template<typename FloatVectorT >
float pcl::B_Norm (FloatVectorT A, FloatVectorT B, int dim)
 Compute the B norm of the vector between two points. More...
 
template<typename FloatVectorT >
float pcl::Sublinear_Norm (FloatVectorT A, FloatVectorT B, int dim)
 Compute the sublinear norm of the vector between two points. More...
 
template<typename FloatVectorT >
float pcl::CS_Norm (FloatVectorT A, FloatVectorT B, int dim)
 Compute the CS norm of the vector between two points. More...
 
template<typename FloatVectorT >
float pcl::Div_Norm (FloatVectorT A, FloatVectorT B, int dim)
 Compute the div norm of the vector between two points. More...
 
template<typename FloatVectorT >
float pcl::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 pcl::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 pcl::KL_Norm (FloatVectorT A, FloatVectorT B, int dim)
 Compute the KL between two discrete probability density functions. More...
 
template<typename FloatVectorT >
float pcl::HIK_Norm (FloatVectorT A, FloatVectorT B, int dim)
 Compute the HIK norm of the vector between two points. More...
 
template<typename PointT , typename Scalar >
void pcl::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 , typename Scalar >
void pcl::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 , typename Scalar >
void pcl::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 , typename Scalar >
void pcl::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 pcl::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...
 
template<typename PointT , typename Scalar >
void pcl::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 , typename Scalar >
void pcl::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 pcl::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 pcl::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 , typename Scalar >
void pcl::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 pcl::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...
 
void pcl::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 >
PointT pcl::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 pcl::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...
 
bool pcl::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...
 

Macro Definition Documentation

◆ PCL_FALLTHROUGH

#define PCL_FALLTHROUGH

#include <pcl/pcl_macros.h>

Macro to add a no-op or a fallthrough attribute based on compiler feature.

Definition at line 433 of file pcl_macros.h.

◆ PCL_MAKE_ALIGNED_OPERATOR_NEW

#define PCL_MAKE_ALIGNED_OPERATOR_NEW

#include <pcl/memory.h>

Value:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW \
using _custom_allocator_type_trait = void;

Macro to signal a class requires a custom allocator.

It's an implementation detail to have pcl::has_custom_allocator work, a thin wrapper over Eigen's own macro

See also
pcl::has_custom_allocator, pcl::make_shared

Definition at line 63 of file memory.h.

Typedef Documentation

◆ BorderTraits

using pcl::BorderTraits = typedef std::bitset<32>

#include <pcl/point_types.h>

Data type to store extended information about a transition from foreground to backgroundSpecification of the fields for BorderDescription::traits.

Definition at line 307 of file point_types.h.

Enumeration Type Documentation

◆ BorderTrait

#include <pcl/point_types.h>

Specification of the fields for BorderDescription::traits.

Enumerator
BORDER_TRAIT__OBSTACLE_BORDER 
BORDER_TRAIT__SHADOW_BORDER 
BORDER_TRAIT__VEIL_POINT 
BORDER_TRAIT__SHADOW_BORDER_TOP 
BORDER_TRAIT__SHADOW_BORDER_RIGHT 
BORDER_TRAIT__SHADOW_BORDER_BOTTOM 
BORDER_TRAIT__SHADOW_BORDER_LEFT 
BORDER_TRAIT__OBSTACLE_BORDER_TOP 
BORDER_TRAIT__OBSTACLE_BORDER_RIGHT 
BORDER_TRAIT__OBSTACLE_BORDER_BOTTOM 
BORDER_TRAIT__OBSTACLE_BORDER_LEFT 
BORDER_TRAIT__VEIL_POINT_TOP 
BORDER_TRAIT__VEIL_POINT_RIGHT 
BORDER_TRAIT__VEIL_POINT_BOTTOM 
BORDER_TRAIT__VEIL_POINT_LEFT 

Definition at line 312 of file point_types.h.

◆ NormType

#include <pcl/common/norms.h>

Enum that defines all the types of norms available.

Note
Any new norm type should have its own enum value and its own case in the selectNorm () method
Enumerator
L1 
L2_SQR 
L2 
LINF 
JM 
SUBLINEAR 
CS 
DIV 
PF 
KL 
HIK 

Definition at line 54 of file norms.h.

Function Documentation

◆ B_Norm()

template<typename FloatVectorT >
float pcl::B_Norm ( FloatVectorT  A,
FloatVectorT  B,
int  dim 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the B norm of the vector between two points.

Parameters
Athe first point
Bthe second point
dimthe number of dimensions in A and B (dimensions must match)
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 140 of file norms.hpp.

Referenced by pcl::selectNorm().

◆ calculatePolygonArea()

template<typename PointT >
float pcl::calculatePolygonArea ( const pcl::PointCloud< PointT > &  polygon)
inline

#include <pcl/common/common.h>

Calculate the area of a polygon given a point cloud that defines the polygon.

Parameters
polygonpoint cloud that contains those vertices that comprises the polygon. Vertices are stored in counterclockwise.
Returns
the polygon area

Definition at line 414 of file common.hpp.

References pcl::PointCloud< PointT >::size().

◆ compute3DCentroid() [1/4]

template<typename PointT , typename Scalar >
unsigned int pcl::compute3DCentroid ( const pcl::PointCloud< PointT > &  cloud,
const Indices indices,
Eigen::Matrix< Scalar, 4, 1 > &  centroid 
)
inline

#include <pcl/common/centroid.h>

Compute the 3D (X-Y-Z) centroid of a set of points using their indices and return it as a 3D vector.

Parameters
[in]cloudthe input point cloud
[in]indicesthe point cloud indices that need to be used
[out]centroidthe output centroid
Returns
number of valid points used to determine the centroid. In case of dense point clouds, this is the same as the size of input indices.
Note
if return value is 0, the centroid is not changed, thus not valid. The last component of the vector is set to 1, this allows to transform the centroid vector with 4x4 matrices.

Definition at line 137 of file centroid.hpp.

References pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().

◆ compute3DCentroid() [2/4]

template<typename PointT , typename Scalar >
unsigned int pcl::compute3DCentroid ( const pcl::PointCloud< PointT > &  cloud,
const pcl::PointIndices indices,
Eigen::Matrix< Scalar, 4, 1 > &  centroid 
)
inline

#include <pcl/common/centroid.h>

Compute the 3D (X-Y-Z) centroid of a set of points using their indices and return it as a 3D vector.

Parameters
[in]cloudthe input point cloud
[in]indicesthe point cloud indices that need to be used
[out]centroidthe output centroid
Returns
number of valid points used to determine the centroid. In case of dense point clouds, this is the same as the size of input indices.
Note
if return value is 0, the centroid is not changed, thus not valid. The last component of the vector is set to 1, this allows to transform the centroid vector with 4x4 matrices.

Definition at line 183 of file centroid.hpp.

References pcl::compute3DCentroid(), and pcl::PointIndices::indices.

◆ compute3DCentroid() [3/4]

template<typename PointT , typename Scalar >
unsigned int pcl::compute3DCentroid ( const pcl::PointCloud< PointT > &  cloud,
Eigen::Matrix< Scalar, 4, 1 > &  centroid 
)
inline

#include <pcl/common/centroid.h>

Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector.

Parameters
[in]cloudthe input point cloud
[out]centroidthe output centroid
Returns
number of valid points used to determine the centroid. In case of dense point clouds, this is the same as the size of input cloud.
Note
if return value is 0, the centroid is not changed, thus not valid. The last component of the vector is set to 1, this allows to transform the centroid vector with 4x4 matrices.

Definition at line 89 of file centroid.hpp.

References pcl::PointCloud< PointT >::empty(), pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().

◆ compute3DCentroid() [4/4]

template<typename PointT , typename Scalar >
unsigned int pcl::compute3DCentroid ( ConstCloudIterator< PointT > &  cloud_iterator,
Eigen::Matrix< Scalar, 4, 1 > &  centroid 
)
inline

#include <pcl/common/centroid.h>

Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector.

Parameters
[in]cloud_iteratoran iterator over the input point cloud
[out]centroidthe output centroid
Returns
number of valid points used to determine the centroid. In case of dense point clouds, this is the same as the size of input cloud.
Note
if return value is 0, the centroid is not changed, thus not valid. The last component of the vector is set to 1, this allows to transform the centroid vector with 4x4 matrices.

Definition at line 57 of file centroid.hpp.

References pcl::isFinite(), and pcl::ConstCloudIterator< PointT >::isValid().

Referenced by pcl::gpu::people::buildTree(), pcl::ConvexHull< PointInT >::calculateInputDimension(), pcl::compute3DCentroid(), pcl::MLSResult::computeMLSSurface(), pcl::MomentInvariantsEstimation< PointInT, PointOutT >::computePointMomentInvariants(), pcl::registration::TransformationEstimation2D< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimation3Point< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::linkMatchWithBase(), pcl::SampleConsensusModelLine< PointT >::optimizeModelCoefficients(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::ESFEstimation< PointInT, PointOutT >::scale_points_unit_sphere(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, pcl::Normal, float >::selectBaseTriangle(), and pcl::gpu::people::label_skeleton::sortIndicesToBlob2().

◆ computeCentroid() [1/2]

template<typename PointInT , typename PointOutT >
std::size_t pcl::computeCentroid ( const pcl::PointCloud< PointInT > &  cloud,
const Indices indices,
PointOutT &  centroid 
)

#include <pcl/common/centroid.h>

Compute the centroid of a set of points and return it as a point.

Parameters
[in]cloud
[in]indicespoint cloud indices that need to be used
[out]centroidThis is an overloaded function provided for convenience. See the documentation for computeCentroid().

Definition at line 1206 of file centroid.hpp.

References pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().

◆ computeCentroid() [2/2]

template<typename PointInT , typename PointOutT >
std::size_t pcl::computeCentroid ( const pcl::PointCloud< PointInT > &  cloud,
PointOutT &  centroid 
)

#include <pcl/common/centroid.h>

Compute the centroid of a set of points and return it as a point.

Implementation leverages CentroidPoint class and therefore behaves differently from compute3DCentroid() and computeNDCentroid(). See CentroidPoint documentation for explanation.

Parameters
[in]cloudinput point cloud
[out]centroidoutput centroid
Returns
number of valid points used to determine the centroid (will be the same as the size of the cloud if it is dense)
Note
If return value is 0, then the centroid is not changed, thus is not valid.

Definition at line 1187 of file centroid.hpp.

References pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().

◆ computeCentroidAndOBB() [1/2]

template<typename PointT , typename Scalar >
unsigned int pcl::computeCentroidAndOBB ( const pcl::PointCloud< PointT > &  cloud,
const Indices indices,
Eigen::Matrix< Scalar, 3, 1 > &  centroid,
Eigen::Matrix< Scalar, 3, 1 > &  obb_center,
Eigen::Matrix< Scalar, 3, 1 > &  obb_dimensions,
Eigen::Matrix< Scalar, 3, 3 > &  obb_rotational_matrix 
)
inline

#include <pcl/common/centroid.h>

Compute centroid, OBB (Oriented Bounding Box), PCA axes of a given set of points.

OBB is oriented like the three axes (major, middle and minor) with major_axis = obb_rotational_matrix.col(0) middle_axis = obb_rotational_matrix.col(1) minor_axis = obb_rotational_matrix.col(2) one way to visualize OBB when Scalar is float: Eigen::Vector3f position(obb_position(0), obb_position(1), obb_position(2)); Eigen::Quaternionf quat(obb_rotational_matrix); viewer->addCube(position, quat, obb_dimensions(0), obb_dimensions(1), obb_dimensions(2), .....);

Parameters
[in]cloudthe input point cloud
[in]indicessubset of points given by their indices
[out]centroidthe centroid (mean value of the XYZ coordinates) of the set of points in the cloud
[out]obb_centerposition of the center of the OBB (it is the same as centroid if the cloud is centrally symmetric)
[out]obb_dimensions(width, height and depth) of the OBB
[out]obb_rotational_matrixrotational matrix of the OBB
Returns
number of valid points used to determine the output. In case of dense point clouds, this is the same as the size of the input cloud.

Definition at line 796 of file centroid.hpp.

References pcl::computeMeanAndCovarianceMatrix(), pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().

◆ computeCentroidAndOBB() [2/2]

template<typename PointT , typename Scalar >
unsigned int pcl::computeCentroidAndOBB ( const pcl::PointCloud< PointT > &  cloud,
Eigen::Matrix< Scalar, 3, 1 > &  centroid,
Eigen::Matrix< Scalar, 3, 1 > &  obb_center,
Eigen::Matrix< Scalar, 3, 1 > &  obb_dimensions,
Eigen::Matrix< Scalar, 3, 3 > &  obb_rotational_matrix 
)
inline

#include <pcl/common/centroid.h>

Compute centroid, OBB (Oriented Bounding Box), PCA axes of a given set of points.

OBB is oriented like the three axes (major, middle and minor) with major_axis = obb_rotational_matrix.col(0) middle_axis = obb_rotational_matrix.col(1) minor_axis = obb_rotational_matrix.col(2) one way to visualize OBB when Scalar is float: Eigen::Vector3f position(obb_position(0), obb_position(1), obb_position(2)); Eigen::Quaternionf quat(obb_rotational_matrix); viewer->addCube(position, quat, obb_dimensions(0), obb_dimensions(1), obb_dimensions(2), .....);

Parameters
[in]cloudthe input point cloud
[out]centroidthe centroid (mean value of the XYZ coordinates) of the set of points in the cloud
[out]obb_centerposition of the center of the OBB (it is the same as centroid if the cloud is centrally symmetric)
[out]obb_dimensions(width, height and depth) of the OBB
[out]obb_rotational_matrixrotational matrix of the OBB
Returns
number of valid points used to determine the output. In case of dense point clouds, this is the same as the size of the input cloud.

Definition at line 663 of file centroid.hpp.

References pcl::computeMeanAndCovarianceMatrix(), pcl::PointCloud< PointT >::is_dense, pcl::isFinite(), and pcl::PointCloud< PointT >::size().

◆ computeCorrespondingEigenVector()

template<typename Matrix , typename Vector >
void pcl::computeCorrespondingEigenVector ( const Matrix &  mat,
const typename Matrix::Scalar &  eigenvalue,
Vector &  eigenvector 
)
inline

#include <pcl/common/eigen.h>

determines the corresponding eigenvector to the given eigenvalue of the symmetric positive semi definite input matrix

Parameters
[in]matsymmetric positive semi definite input matrix
[in]eigenvaluethe eigenvalue which corresponding eigenvector is to be computed
[out]eigenvectorthe corresponding eigenvector for the input eigenvalue

Definition at line 226 of file eigen.hpp.

Referenced by pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::computePointPrincipalCurvatures(), pcl::SampleConsensusModelLine< PointT >::optimizeModelCoefficients(), and pcl::SampleConsensusModelStick< PointT >::optimizeModelCoefficients().

◆ computeCovarianceMatrix() [1/6]

template<typename PointT , typename Scalar >
unsigned int pcl::computeCovarianceMatrix ( const pcl::PointCloud< PointT > &  cloud,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
Eigen::Matrix< Scalar, 3, 3 > &  covariance_matrix 
)
inline

#include <pcl/common/centroid.h>

Compute the 3x3 covariance matrix of a given set of points.

The result is returned as a Eigen::Matrix3f. Note: the covariance matrix is not normalized with the number of points. For a normalized covariance, please use computeCovarianceMatrixNormalized.

Parameters
[in]cloudthe input point cloud
[in]centroidthe centroid of the set of points in the cloud
[out]covariance_matrixthe resultant 3x3 covariance matrix
Returns
number of valid points used to determine the covariance matrix. In case of dense point clouds, this is the same as the size of input cloud.
Note
if return value is 0, the covariance matrix is not changed, thus not valid.

Definition at line 192 of file centroid.hpp.

References pcl::PointCloud< PointT >::empty(), pcl::PointCloud< PointT >::is_dense, pcl::isFinite(), and pcl::PointCloud< PointT >::size().

Referenced by pcl::CovarianceSampling< PointT, PointNT >::applyFilter(), pcl::MomentOfInertiaEstimation< PointT >::compute(), pcl::CovarianceSampling< PointT, PointNT >::computeConditionNumber(), pcl::computeCovarianceMatrix(), pcl::computeCovarianceMatrixNormalized(), pcl::MLSResult::computeMLSSurface(), and pcl::SampleConsensusModelLine< PointT >::optimizeModelCoefficients().

◆ computeCovarianceMatrix() [2/6]

template<typename PointT , typename Scalar >
unsigned int pcl::computeCovarianceMatrix ( const pcl::PointCloud< PointT > &  cloud,
const Indices indices,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
Eigen::Matrix< Scalar, 3, 3 > &  covariance_matrix 
)
inline

#include <pcl/common/centroid.h>

Compute the 3x3 covariance matrix of a given set of points using their indices.

The result is returned as a Eigen::Matrix3f. Note: the covariance matrix is not normalized with the number of points. For a normalized covariance, please use computeCovarianceMatrixNormalized.

Parameters
[in]cloudthe input point cloud
[in]indicesthe point cloud indices that need to be used
[in]centroidthe centroid of the set of points in the cloud
[out]covariance_matrixthe resultant 3x3 covariance matrix
Returns
number of valid points used to determine the covariance matrix. In case of dense point clouds, this is the same as the size of input indices.

Definition at line 281 of file centroid.hpp.

References pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().

◆ computeCovarianceMatrix() [3/6]

template<typename PointT , typename Scalar >
unsigned int pcl::computeCovarianceMatrix ( const pcl::PointCloud< PointT > &  cloud,
const Indices indices,
Eigen::Matrix< Scalar, 3, 3 > &  covariance_matrix 
)
inline

#include <pcl/common/centroid.h>

Compute the normalized 3x3 covariance matrix for a already demeaned point cloud.

Normalized means that every entry has been divided by the number of entries in indices. For small number of points, or if you want explicitly the sample-variance, scale the covariance matrix with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function.

Note
This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency.
Parameters
[in]cloudthe input point cloud
[in]indicessubset of points given by their indices
[out]covariance_matrixthe resultant 3x3 covariance matrix
Returns
number of valid points used to determine the covariance matrix. In case of dense point clouds, this is the same as the size of input indices.

Definition at line 446 of file centroid.hpp.

References pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().

◆ computeCovarianceMatrix() [4/6]

template<typename PointT , typename Scalar >
unsigned int pcl::computeCovarianceMatrix ( const pcl::PointCloud< PointT > &  cloud,
const pcl::PointIndices indices,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
Eigen::Matrix< Scalar, 3, 3 > &  covariance_matrix 
)
inline

#include <pcl/common/centroid.h>

Compute the 3x3 covariance matrix of a given set of points using their indices.

The result is returned as a Eigen::Matrix3f. Note: the covariance matrix is not normalized with the number of points. For a normalized covariance, please use computeCovarianceMatrixNormalized.

Parameters
[in]cloudthe input point cloud
[in]indicesthe point cloud indices that need to be used
[in]centroidthe centroid of the set of points in the cloud
[out]covariance_matrixthe resultant 3x3 covariance matrix
Returns
number of valid points used to determine the covariance matrix. In case of dense point clouds, this is the same as the size of input indices.

Definition at line 358 of file centroid.hpp.

References pcl::computeCovarianceMatrix(), and pcl::PointIndices::indices.

◆ computeCovarianceMatrix() [5/6]

template<typename PointT , typename Scalar >
unsigned int pcl::computeCovarianceMatrix ( const pcl::PointCloud< PointT > &  cloud,
const pcl::PointIndices indices,
Eigen::Matrix< Scalar, 3, 3 > &  covariance_matrix 
)
inline

#include <pcl/common/centroid.h>

Compute the normalized 3x3 covariance matrix for a already demeaned point cloud.

Normalized means that every entry has been divided by the number of entries in indices. For small number of points, or if you want explicitly the sample-variance, scale the covariance matrix with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function.

Note
This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency.
Parameters
[in]cloudthe input point cloud
[in]indicessubset of points given by their indices
[out]covariance_matrixthe resultant 3x3 covariance matrix
Returns
number of valid points used to determine the covariance matrix. In case of dense point clouds, this is the same as the size of input indices.

Definition at line 500 of file centroid.hpp.

References pcl::computeCovarianceMatrix(), and pcl::PointIndices::indices.

◆ computeCovarianceMatrix() [6/6]

template<typename PointT , typename Scalar >
unsigned int pcl::computeCovarianceMatrix ( const pcl::PointCloud< PointT > &  cloud,
Eigen::Matrix< Scalar, 3, 3 > &  covariance_matrix 
)
inline

#include <pcl/common/centroid.h>

Compute the normalized 3x3 covariance matrix for a already demeaned point cloud.

Normalized means that every entry has been divided by the number of entries in the input point cloud. For small number of points, or if you want explicitly the sample-variance, scale the covariance matrix with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function.

Note
This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency.
Parameters
[in]cloudthe input point cloud
[out]covariance_matrixthe resultant 3x3 covariance matrix
Returns
number of valid points used to determine the covariance matrix. In case of dense point clouds, this is the same as the size of input cloud.

Definition at line 392 of file centroid.hpp.

References pcl::PointCloud< PointT >::is_dense, pcl::isFinite(), and pcl::PointCloud< PointT >::size().

◆ computeCovarianceMatrixNormalized() [1/3]

template<typename PointT , typename Scalar >
unsigned int pcl::computeCovarianceMatrixNormalized ( const pcl::PointCloud< PointT > &  cloud,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
Eigen::Matrix< Scalar, 3, 3 > &  covariance_matrix 
)
inline

#include <pcl/common/centroid.h>

Compute normalized the 3x3 covariance matrix of a given set of points.

The result is returned as a Eigen::Matrix3f. Normalized means that every entry has been divided by the number of points in the point cloud. For small number of points, or if you want explicitly the sample-variance, use computeCovarianceMatrix and scale the covariance matrix with 1 / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by the computeCovarianceMatrix function.

Parameters
[in]cloudthe input point cloud
[in]centroidthe centroid of the set of points in the cloud
[out]covariance_matrixthe resultant 3x3 covariance matrix
Returns
number of valid points used to determine the covariance matrix. In case of dense point clouds, this is the same as the size of input cloud.

Definition at line 269 of file centroid.hpp.

References pcl::computeCovarianceMatrix().

Referenced by pcl::gpu::people::buildTree(), pcl::ConvexHull< PointInT >::calculateInputDimension(), pcl::computeCovarianceMatrixNormalized(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), and pcl::gpu::people::label_skeleton::sortIndicesToBlob2().

◆ computeCovarianceMatrixNormalized() [2/3]

template<typename PointT , typename Scalar >
unsigned int pcl::computeCovarianceMatrixNormalized ( const pcl::PointCloud< PointT > &  cloud,
const Indices indices,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
Eigen::Matrix< Scalar, 3, 3 > &  covariance_matrix 
)
inline

#include <pcl/common/centroid.h>

Compute the normalized 3x3 covariance matrix of a given set of points using their indices.

The result is returned as a Eigen::Matrix3f. Normalized means that every entry has been divided by the number of entries in indices. For small number of points, or if you want explicitly the sample-variance, use computeCovarianceMatrix and scale the covariance matrix with 1 / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by the computeCovarianceMatrix function.

Parameters
[in]cloudthe input point cloud
[in]indicesthe point cloud indices that need to be used
[in]centroidthe centroid of the set of points in the cloud
[out]covariance_matrixthe resultant 3x3 covariance matrix
Returns
number of valid points used to determine the covariance matrix. In case of dense point clouds, this is the same as the size of input indices.

Definition at line 368 of file centroid.hpp.

References pcl::computeCovarianceMatrix().

◆ computeCovarianceMatrixNormalized() [3/3]

template<typename PointT , typename Scalar >
unsigned int pcl::computeCovarianceMatrixNormalized ( const pcl::PointCloud< PointT > &  cloud,
const pcl::PointIndices indices,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
Eigen::Matrix< Scalar, 3, 3 > &  covariance_matrix 
)
inline

#include <pcl/common/centroid.h>

Compute the normalized 3x3 covariance matrix of a given set of points using their indices.

The result is returned as a Eigen::Matrix3f. Normalized means that every entry has been divided by the number of entries in indices. For small number of points, or if you want explicitly the sample-variance, use computeCovarianceMatrix and scale the covariance matrix with 1 / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by the computeCovarianceMatrix function.

Parameters
[in]cloudthe input point cloud
[in]indicesthe point cloud indices that need to be used
[in]centroidthe centroid of the set of points in the cloud
[out]covariance_matrixthe resultant 3x3 covariance matrix
Returns
number of valid points used to determine the covariance matrix. In case of dense point clouds, this is the same as the size of input indices.

Definition at line 382 of file centroid.hpp.

References pcl::computeCovarianceMatrixNormalized(), and pcl::PointIndices::indices.

◆ computeMeanAndCovarianceMatrix() [1/3]

template<typename PointT , typename Scalar >
unsigned int pcl::computeMeanAndCovarianceMatrix ( const pcl::PointCloud< PointT > &  cloud,
const Indices indices,
Eigen::Matrix< Scalar, 3, 3 > &  covariance_matrix,
Eigen::Matrix< Scalar, 4, 1 > &  centroid 
)
inline

#include <pcl/common/centroid.h>

Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop.

Normalized means that every entry has been divided by the number of entries in indices. For small number of points, or if you want explicitly the sample-variance, scale the covariance matrix with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function.

Note
This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency.
Parameters
[in]cloudthe input point cloud
[in]indicessubset of points given by their indices
[out]covariance_matrixthe resultant 3x3 covariance matrix
[out]centroidthe centroid of the set of points in the cloud
Returns
number of valid points used to determine the covariance matrix. In case of dense point clouds, this is the same as the size of input indices.

Definition at line 581 of file centroid.hpp.

References pcl::PointCloud< PointT >::is_dense, pcl::isFinite(), pcl::K, and pcl::PointCloud< PointT >::size().

◆ computeMeanAndCovarianceMatrix() [2/3]

template<typename PointT , typename Scalar >
unsigned int pcl::computeMeanAndCovarianceMatrix ( const pcl::PointCloud< PointT > &  cloud,
const pcl::PointIndices indices,
Eigen::Matrix< Scalar, 3, 3 > &  covariance_matrix,
Eigen::Matrix< Scalar, 4, 1 > &  centroid 
)
inline

#include <pcl/common/centroid.h>

Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop.

Normalized means that every entry has been divided by the number of entries in indices. For small number of points, or if you want explicitly the sample-variance, scale the covariance matrix with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function.

Note
This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency.
Parameters
[in]cloudthe input point cloud
[in]indicessubset of points given by their indices
[out]centroidthe centroid of the set of points in the cloud
[out]covariance_matrixthe resultant 3x3 covariance matrix
Returns
number of valid points used to determine the covariance matrix. In case of dense point clouds, this is the same as the size of input indices.

Definition at line 654 of file centroid.hpp.

References pcl::computeMeanAndCovarianceMatrix(), and pcl::PointIndices::indices.

◆ computeMeanAndCovarianceMatrix() [3/3]

template<typename PointT , typename Scalar >
unsigned int pcl::computeMeanAndCovarianceMatrix ( const pcl::PointCloud< PointT > &  cloud,
Eigen::Matrix< Scalar, 3, 3 > &  covariance_matrix,
Eigen::Matrix< Scalar, 4, 1 > &  centroid 
)
inline

#include <pcl/common/centroid.h>

Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop.

Normalized means that every entry has been divided by the number of valid entries in the point cloud. For small number of points, or if you want explicitly the sample-variance, scale the covariance matrix with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function.

Note
This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency.
Parameters
[in]cloudthe input point cloud
[out]covariance_matrixthe resultant 3x3 covariance matrix
[out]centroidthe centroid of the set of points in the cloud
Returns
number of valid points used to determine the covariance matrix. In case of dense point clouds, this is the same as the size of input cloud.

Definition at line 509 of file centroid.hpp.

References pcl::PointCloud< PointT >::is_dense, pcl::isFinite(), pcl::K, and pcl::PointCloud< PointT >::size().

Referenced by pcl::computeCentroidAndOBB(), pcl::computeMeanAndCovarianceMatrix(), pcl::NormalEstimation< PointInT, PointOutT >::computePointNormal(), pcl::computePointNormal(), pcl::SampleConsensusModelRegistration< PointT >::computeSampleDistanceThreshold(), pcl::getPrincipalTransformation(), pcl::GridProjection< PointNT >::getProjectionWithPlaneFit(), pcl::isPointIn2DPolygon(), pcl::SampleConsensusModelPlane< PointT >::optimizeModelCoefficients(), pcl::SampleConsensusModelStick< PointT >::optimizeModelCoefficients(), pcl::ExtractPolygonalPrismData< PointT >::segment(), and pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment().

◆ computeMedian()

template<typename IteratorT , typename Functor >
auto pcl::computeMedian ( IteratorT  begin,
IteratorT  end,
Functor  f 
) -> std::result_of_t<Functor(decltype(*begin))>
inlinenoexcept

#include <pcl/common/common.h>

Compute the median of a list of values (fast).

If the number of values is even, take the mean of the two middle values. This function can be used like this:

std::vector<double> vector{1.0, 25.0, 9.0, 4.0, 16.0};
const double median = pcl::computeMedian (vector.begin (), vector.end (), static_cast<double(*)(double)>(std::sqrt)); // = 3
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).
Definition: common.h:285
Parameters
[in,out]begin,endIterators that mark the beginning and end of the value range. These values will be reordered!
[in]fA lamda, function pointer, or similar that is implicitly applied to all values before median computation. In reality, it will be applied lazily (i.e. at most twice) and thus may not change the sorting order (e.g. monotonic functions like sqrt are allowed)
Returns
the median

Definition at line 285 of file common.h.

References pcl::geometry::distance().

Referenced by pcl::MaximumLikelihoodSampleConsensus< PointT >::computeMedian(), pcl::computeMedian(), pcl::MaximumLikelihoodSampleConsensus< PointT >::computeMedianAbsoluteDeviation(), and pcl::LeastMedianSquares< PointT >::computeModel().

◆ computeNDCentroid() [1/3]

template<typename PointT , typename Scalar >
void pcl::computeNDCentroid ( const pcl::PointCloud< PointT > &  cloud,
const Indices indices,
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &  centroid 
)
inline

#include <pcl/common/centroid.h>

General, all purpose nD centroid estimation for a set of points using their indices.

Parameters
cloudthe input point cloud
indicesthe point cloud indices that need to be used
centroidthe output centroid

Definition at line 1133 of file centroid.hpp.

◆ computeNDCentroid() [2/3]

template<typename PointT , typename Scalar >
void pcl::computeNDCentroid ( const pcl::PointCloud< PointT > &  cloud,
const pcl::PointIndices indices,
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &  centroid 
)
inline

#include <pcl/common/centroid.h>

General, all purpose nD centroid estimation for a set of points using their indices.

Parameters
cloudthe input point cloud
indicesthe point cloud indices that need to be used
centroidthe output centroid

Definition at line 1156 of file centroid.hpp.

References pcl::computeNDCentroid(), and pcl::PointIndices::indices.

◆ computeNDCentroid() [3/3]

template<typename PointT , typename Scalar >
void pcl::computeNDCentroid ( const pcl::PointCloud< PointT > &  cloud,
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &  centroid 
)
inline

#include <pcl/common/centroid.h>

General, all purpose nD centroid estimation for a set of points using their indices.

Parameters
cloudthe input point cloud
centroidthe output centroid

Definition at line 1111 of file centroid.hpp.

References pcl::PointCloud< PointT >::empty(), and pcl::PointCloud< PointT >::size().

Referenced by pcl::computeNDCentroid().

◆ concatenate() [1/3]

PCL_EXPORTS bool pcl::concatenate ( const pcl::PCLPointCloud2 cloud1,
const pcl::PCLPointCloud2 cloud2,
pcl::PCLPointCloud2 cloud_out 
)
inline

#include <pcl/common/io.h>

Concatenate two pcl::PCLPointCloud2.

Warning
This function will concatenate IFF the non-skip fields are in the correct order and same in number.
Parameters
[in]cloud1the first input point cloud dataset
[in]cloud2the second input point cloud dataset
[out]cloud_outthe resultant output point cloud dataset
Returns
true if successful, false otherwise

Definition at line 299 of file io.h.

References pcl::PCLPointCloud2::concatenate().

◆ concatenate() [2/3]

template<typename PointT >
PCL_EXPORTS bool pcl::concatenate ( const pcl::PointCloud< PointT > &  cloud1,
const pcl::PointCloud< PointT > &  cloud2,
pcl::PointCloud< PointT > &  cloud_out 
)

#include <pcl/common/io.h>

Concatenate two pcl::PointCloud<PointT>

Parameters
[in]cloud1the first input point cloud dataset
[in]cloud2the second input point cloud dataset
[out]cloud_outthe resultant output point cloud dataset
Returns
true if successful, false otherwise

Definition at line 281 of file io.h.

References pcl::PointCloud< PointT >::concatenate().

Referenced by pcl::PointCloud< PointT >::concatenate(), pcl::PCLPointCloud2::concatenate(), pcl::PolygonMesh::concatenate(), pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::insertRange(), pcl::PointCloud< PointT >::operator+=(), pcl::PolygonMesh::operator+=(), pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes(), pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes_subsample(), and pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::read().

◆ concatenate() [3/3]

PCL_EXPORTS bool pcl::concatenate ( const pcl::PolygonMesh mesh1,
const pcl::PolygonMesh mesh2,
pcl::PolygonMesh mesh_out 
)
inline

#include <pcl/common/io.h>

Concatenate two pcl::PolygonMesh.

Parameters
[in]mesh1the first input mesh
[in]mesh2the second input mesh
[out]mesh_outthe resultant output mesh
Returns
true if successful, false otherwise

Definition at line 314 of file io.h.

References pcl::PolygonMesh::concatenate().

◆ concatenateFields() [1/2]

PCL_EXPORTS bool pcl::concatenateFields ( const pcl::PCLPointCloud2 cloud1_in,
const pcl::PCLPointCloud2 cloud2_in,
pcl::PCLPointCloud2 cloud_out 
)

#include <pcl/common/io.h>

Concatenate two datasets representing different fields.

Note
If the input datasets have overlapping fields (i.e., both contain the same fields), then the data in the second cloud (cloud2_in) will overwrite the data in the first (cloud1_in).
Parameters
[in]cloud1_inthe first input dataset
[in]cloud2_inthe second input dataset (overwrites the fields of the first dataset for those that are shared)
[out]cloud_outthe output dataset created by concatenating all the fields in the input datasets

◆ concatenateFields() [2/2]

template<typename PointIn1T , typename PointIn2T , typename PointOutT >
void pcl::concatenateFields ( const pcl::PointCloud< PointIn1T > &  cloud1_in,
const pcl::PointCloud< PointIn2T > &  cloud2_in,
pcl::PointCloud< PointOutT > &  cloud_out 
)

#include <pcl/common/impl/io.hpp>

Concatenate two datasets representing different fields.

Note
If the input datasets have overlapping fields (i.e., both contain the same fields), then the data in the second cloud (cloud2_in) will overwrite the data in the first (cloud1_in).
Parameters
[in]cloud1_inthe first input dataset
[in]cloud2_inthe second input dataset (overwrites the fields of the first dataset for those that are shared)
[out]cloud_outthe resultant output dataset created by the concatenation of all the fields in the input datasets

Definition at line 303 of file io.hpp.

References pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::resize(), pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.

◆ copyPoint()

template<typename PointInT , typename PointOutT >
void pcl::copyPoint ( const PointInT &  point_in,
PointOutT &  point_out 
)

#include <pcl/common/copy_point.h>

Copy the fields of a source point into a target point.

If the source and the target point types are the same, then a complete copy is made. Otherwise only those fields that the two point types share in common are copied.

Parameters
[in]point_inthe source point
[out]point_outthe target point

Definition at line 137 of file copy_point.hpp.

Referenced by pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::FilterIndices< PointT >::applyFilter(), pcl::MovingLeastSquares< PointInT, PointOutT >::copyMissingFields(), pcl::copyPointCloud(), pcl::detail::copyPointCloudMemcpy(), pcl::gpu::extractEuclideanClusters(), pcl::search::Search< PointT >::nearestKSearchT(), pcl::KdTree< PointT >::nearestKSearchT(), pcl::registration::detail::pointCopyOrRef(), pcl::KdTree< PointT >::radiusSearchT(), and pcl::search::Search< PointT >::radiusSearchT().

◆ copyPointCloud() [1/11]

PCL_EXPORTS void pcl::copyPointCloud ( const pcl::PCLPointCloud2 cloud_in,
const Indices indices,
pcl::PCLPointCloud2 cloud_out 
)

#include <pcl/common/io.h>

Extract the indices of a given point cloud as a new point cloud.

Parameters
[in]cloud_inthe input point cloud dataset
[in]indicesthe vector of indices representing the points to be copied from cloud_in
[out]cloud_outthe resultant output point cloud dataset
Note
Assumes unique indices.

◆ copyPointCloud() [2/11]

PCL_EXPORTS void pcl::copyPointCloud ( const pcl::PCLPointCloud2 cloud_in,
const IndicesAllocator< Eigen::aligned_allocator< index_t > > &  indices,
pcl::PCLPointCloud2 cloud_out 
)

#include <pcl/common/io.h>

Extract the indices of a given point cloud as a new point cloud.

Parameters
[in]cloud_inthe input point cloud dataset
[in]indicesthe vector of indices representing the points to be copied from cloud_in
[out]cloud_outthe resultant output point cloud dataset
Note
Assumes unique indices.

◆ copyPointCloud() [3/11]

PCL_EXPORTS void pcl::copyPointCloud ( const pcl::PCLPointCloud2 cloud_in,
pcl::PCLPointCloud2 cloud_out 
)

#include <pcl/common/io.h>

Copy fields and point cloud data from cloud_in to cloud_out.

Parameters
[in]cloud_inthe input point cloud dataset
[out]cloud_outthe resultant output point cloud dataset

◆ copyPointCloud() [4/11]

template<typename PointInT , typename PointOutT , typename IndicesVectorAllocator >
void pcl::copyPointCloud ( const pcl::PointCloud< PointInT > &  cloud_in,
const IndicesAllocator< IndicesVectorAllocator > &  indices,
pcl::PointCloud< PointOutT > &  cloud_out 
)

#include <pcl/common/impl/io.hpp>

Extract the indices of a given point cloud as a new point cloud.

Parameters
[in]cloud_inthe input point cloud dataset
[in]indicesthe vector of indices representing the points to be copied from cloud_in
[out]cloud_outthe resultant output point cloud dataset
Note
Assumes unique indices.

Definition at line 188 of file io.hpp.

References pcl::copyPoint(), pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::resize(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, and pcl::PointCloud< PointT >::width.

◆ copyPointCloud() [5/11]

template<typename PointInT , typename PointOutT >
void pcl::copyPointCloud ( const pcl::PointCloud< PointInT > &  cloud_in,
const PointIndices indices,
pcl::PointCloud< PointOutT > &  cloud_out 
)

#include <pcl/common/impl/io.hpp>

Extract the indices of a given point cloud as a new point cloud.

Parameters
[in]cloud_inthe input point cloud dataset
[in]indicesthe PointIndices structure representing the points to be copied from cloud_in
[out]cloud_outthe resultant output point cloud dataset
Note
Assumes unique indices.

Definition at line 217 of file io.hpp.

References pcl::copyPointCloud(), and pcl::PointIndices::indices.

◆ copyPointCloud() [6/11]

template<typename PointInT , typename PointOutT >
void pcl::copyPointCloud ( const pcl::PointCloud< PointInT > &  cloud_in,
const std::vector< pcl::PointIndices > &  indices,
pcl::PointCloud< PointOutT > &  cloud_out 
)

#include <pcl/common/impl/io.hpp>

Extract the indices of a given point cloud as a new point cloud.

Parameters
[in]cloud_inthe input point cloud dataset
[in]indicesthe vector of indices representing the points to be copied from cloud_in
[out]cloud_outthe resultant output point cloud dataset
Note
Assumes unique indices.

Definition at line 265 of file io.hpp.

References pcl::copyPoint(), pcl::copyPointCloud(), pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::resize(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.

◆ copyPointCloud() [7/11]

template<typename PointInT , typename PointOutT >
void pcl::copyPointCloud ( const pcl::PointCloud< PointInT > &  cloud_in,
pcl::PointCloud< PointOutT > &  cloud_out 
)

#include <pcl/common/impl/io.hpp>

Copy all the fields from a given point cloud into a new point cloud.

Parameters
[in]cloud_inthe input point cloud dataset
[out]cloud_outthe resultant output point cloud dataset

Definition at line 142 of file io.hpp.

References pcl::detail::copyPointCloudMemcpy(), pcl::PointCloud< PointT >::empty(), pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::resize(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.

Referenced by pcl::HypothesisVerification< ModelT, SceneT >::addModels(), pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::addPointCloud(), pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::addPointCloud_and_genLOD(), pcl::LineRGBD< PointXYZT, PointRGBT >::addTemplate(), pcl::keypoints::internal::AgastApplyNonMaxSuppresion< Out >::AgastApplyNonMaxSuppresion(), pcl::keypoints::internal::AgastDetector< Out >::AgastDetector(), pcl::ExtractIndices< PointT >::applyFilter(), pcl::FastBilateralFilter< PointT >::applyFilter(), pcl::FastBilateralFilterOMP< PointT >::applyFilter(), pcl::FilterIndices< PointT >::applyFilter(), pcl::MedianFilter< PointT >::applyFilter(), ObjectRecognition::applyFiltersAndSegment(), pcl::applyMorphologicalOperator(), pcl::GeometricConsistencyGrouping< PointModelT, PointSceneT >::clusterCorrespondences(), pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::clusterCorrespondences(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::computePyramids(), pcl::copyPointCloud(), pcl::LineRGBD< PointXYZT, PointRGBT >::createAndAddTemplate(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::BriskKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::Filter< PointT >::filter(), pcl::occlusion_reasoning::ZBuffering< ModelT, SceneT >::filter(), pcl::occlusion_reasoning::filter(), pcl::SupervoxelClustering< PointT >::getLabeledCloud(), pcl::SupervoxelClustering< PointT >::getLabeledVoxelCloud(), pcl::occlusion_reasoning::getOccludedCloud(), pcl::getPointCloudDifference(), pcl::SupervoxelClustering< PointT >::getVoxelCentroidCloud(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes(), and pcl::io::savePLYFile().

◆ copyPointCloud() [8/11]

template<typename PointT , typename IndicesVectorAllocator >
void pcl::copyPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
const IndicesAllocator< IndicesVectorAllocator > &  indices,
pcl::PointCloud< PointT > &  cloud_out 
)

#include <pcl/common/impl/io.hpp>

Extract the indices of a given point cloud as a new point cloud.

Parameters
[in]cloud_inthe input point cloud dataset
[in]indicesthe vector of indices representing the points to be copied from cloud_in
[out]cloud_outthe resultant output point cloud dataset
Note
Assumes unique indices.

Definition at line 160 of file io.hpp.

References pcl::PointCloud< PointT >::clear(), pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::reserve(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), pcl::PointCloud< PointT >::transient_push_back(), and pcl::PointCloud< PointT >::width.

◆ copyPointCloud() [9/11]

template<typename PointT >
void pcl::copyPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
const PointIndices indices,
pcl::PointCloud< PointT > &  cloud_out 
)

#include <pcl/common/impl/io.hpp>

Extract the indices of a given point cloud as a new point cloud.

Parameters
[in]cloud_inthe input point cloud dataset
[in]indicesthe PointIndices structure representing the points to be copied from cloud_in
[out]cloud_outthe resultant output point cloud dataset
Note
Assumes unique indices.

Definition at line 208 of file io.hpp.

References pcl::copyPointCloud(), and pcl::PointIndices::indices.

◆ copyPointCloud() [10/11]

template<typename PointT >
void pcl::copyPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
const std::vector< pcl::PointIndices > &  indices,
pcl::PointCloud< PointT > &  cloud_out 
)

#include <pcl/common/impl/io.hpp>

Extract the indices of a given point cloud as a new point cloud.

Parameters
[in]cloud_inthe input point cloud dataset
[in]indicesthe vector of indices representing the points to be copied from cloud_in
[out]cloud_outthe resultant output point cloud dataset
Note
Assumes unique indices.

Definition at line 226 of file io.hpp.

References pcl::PointCloud< PointT >::clear(), pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::reserve(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), pcl::PointCloud< PointT >::transient_push_back(), and pcl::PointCloud< PointT >::width.

◆ copyPointCloud() [11/11]

template<typename PointT >
void pcl::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 
)

#include <pcl/common/impl/io.hpp>

Copy a point cloud inside a larger one interpolating borders.

Parameters
[in]cloud_inthe input point cloud dataset
[out]cloud_outthe resultant output point cloud dataset
top
bottom
left
rightPosition of cloud_in inside cloud_out is given by top, left, bottom right.
[in]border_typethe interpolating method (pcl::BORDER_XXX) BORDER_REPLICATE: aaaaaa|abcdefgh|hhhhhhh BORDER_REFLECT: fedcba|abcdefgh|hgfedcb BORDER_REFLECT_101: gfedcb|abcdefgh|gfedcba BORDER_WRAP: cdefgh|abcdefgh|abcdefg BORDER_CONSTANT: iiiiii|abcdefgh|iiiiiii with some specified 'i' BORDER_TRANSPARENT: mnopqr|abcdefgh|tuvwxyz where m-r and t-z are original values of cloud_out
value
Exceptions
pcl::BadArgumentExceptionif any of top, bottom, left or right is negative.

Definition at line 337 of file io.hpp.

References pcl::BORDER_CONSTANT, pcl::BORDER_TRANSPARENT, pcl::PointCloud< PointT >::data(), pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::interpolatePointIndex(), pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::resize(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.

◆ CS_Norm()

template<typename FloatVectorT >
float pcl::CS_Norm ( FloatVectorT  A,
FloatVectorT  B,
int  dim 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the CS norm of the vector between two points.

Parameters
Athe first point
Bthe second point
dimthe number of dimensions in A and B (dimensions must match)
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 169 of file norms.hpp.

Referenced by pcl::selectNorm().

◆ deg2rad() [1/2]

double pcl::deg2rad ( double  alpha)
inline

#include <pcl/common/angles.h>

Convert an angle from degrees to radians.

Parameters
alphathe input angle (in degrees)

Definition at line 79 of file angles.hpp.

◆ deg2rad() [2/2]

float pcl::deg2rad ( float  alpha)
inline

◆ demeanPointCloud() [1/8]

template<typename PointT , typename Scalar >
void pcl::demeanPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > &  cloud_out 
)

#include <pcl/common/centroid.h>

Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix.

Parameters
[in]cloud_inthe input point cloud
[in]centroidthe centroid of the point cloud
[out]cloud_outthe resultant output XYZ0 dimensions of cloud_in as an Eigen matrix (4 rows, N pts columns)

Definition at line 1054 of file centroid.hpp.

References pcl::PointCloud< PointT >::size().

◆ demeanPointCloud() [2/8]

template<typename PointT , typename Scalar >
void pcl::demeanPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
pcl::PointCloud< PointT > &  cloud_out 
)

#include <pcl/common/centroid.h>

Subtract a centroid from a point cloud and return the de-meaned representation.

Parameters
[in]cloud_inthe input point cloud
[in]centroidthe centroid of the point cloud
[out]cloud_outthe resultant output point cloud

Definition at line 966 of file centroid.hpp.

◆ demeanPointCloud() [3/8]

template<typename PointT , typename Scalar >
void pcl::demeanPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
const Indices indices,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > &  cloud_out 
)

#include <pcl/common/centroid.h>

Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix.

Parameters
[in]cloud_inthe input point cloud
[in]indicesthe set of point indices to use from the input point cloud
[in]centroidthe centroid of the point cloud
[out]cloud_outthe resultant output XYZ0 dimensions of cloud_in as an Eigen matrix (4 rows, N pts columns)

Definition at line 1077 of file centroid.hpp.

◆ demeanPointCloud() [4/8]

template<typename PointT , typename Scalar >
void pcl::demeanPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
const Indices indices,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
pcl::PointCloud< PointT > &  cloud_out 
)

#include <pcl/common/centroid.h>

Subtract a centroid from a point cloud and return the de-meaned representation.

Parameters
[in]cloud_inthe input point cloud
[in]indicesthe set of point indices to use from the input point cloud
[out]centroidthe centroid of the point cloud
cloud_outthe resultant output point cloud

Definition at line 983 of file centroid.hpp.

References pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::resize(), pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.

◆ demeanPointCloud() [5/8]

template<typename PointT , typename Scalar >
void pcl::demeanPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
const pcl::PointIndices indices,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > &  cloud_out 
)

#include <pcl/common/centroid.h>

Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix.

Parameters
[in]cloud_inthe input point cloud
[in]indicesthe set of point indices to use from the input point cloud
[in]centroidthe centroid of the point cloud
[out]cloud_outthe resultant output XYZ0 dimensions of cloud_in as an Eigen matrix (4 rows, N pts columns)

Definition at line 1101 of file centroid.hpp.

References pcl::demeanPointCloud(), and pcl::PointIndices::indices.

◆ demeanPointCloud() [6/8]

template<typename PointT , typename Scalar >
void pcl::demeanPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
const pcl::PointIndices indices,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
pcl::PointCloud< PointT > &  cloud_out 
)

#include <pcl/common/centroid.h>

Subtract a centroid from a point cloud and return the de-meaned representation.

Parameters
[in]cloud_inthe input point cloud
[in]indicesthe set of point indices to use from the input point cloud
[out]centroidthe centroid of the point cloud
cloud_outthe resultant output point cloud

Definition at line 1013 of file centroid.hpp.

References pcl::demeanPointCloud(), and pcl::PointIndices::indices.

◆ demeanPointCloud() [7/8]

template<typename PointT , typename Scalar >
void pcl::demeanPointCloud ( ConstCloudIterator< PointT > &  cloud_iterator,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > &  cloud_out,
int  npts = 0 
)

#include <pcl/common/centroid.h>

Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix.

Parameters
[in]cloud_iteratoran iterator over the input point cloud
[in]centroidthe centroid of the point cloud
[out]cloud_outthe resultant output XYZ0 dimensions of cloud_in as an Eigen matrix (4 rows, N pts columns)
[in]nptsthe number of samples guaranteed to be left in the input cloud, accessible by the iterator. If not given, it will be calculated.

Definition at line 1023 of file centroid.hpp.

References pcl::ConstCloudIterator< PointT >::isValid(), and pcl::ConstCloudIterator< PointT >::reset().

◆ demeanPointCloud() [8/8]

template<typename PointT , typename Scalar >
void pcl::demeanPointCloud ( ConstCloudIterator< PointT > &  cloud_iterator,
const Eigen::Matrix< Scalar, 4, 1 > &  centroid,
pcl::PointCloud< PointT > &  cloud_out,
int  npts = 0 
)

#include <pcl/common/centroid.h>

Subtract a centroid from a point cloud and return the de-meaned representation.

Parameters
[in]cloud_iteratoran iterator over the input point cloud
[in]centroidthe centroid of the point cloud
[out]cloud_outthe resultant output point cloud
[in]nptsthe number of samples guaranteed to be left in the input cloud, accessible by the iterator. If not given, it will be calculated.

Definition at line 933 of file centroid.hpp.

References pcl::PointCloud< PointT >::height, pcl::ConstCloudIterator< PointT >::isValid(), pcl::ConstCloudIterator< PointT >::reset(), pcl::PointCloud< PointT >::resize(), pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.

Referenced by pcl::demeanPointCloud(), pcl::registration::TransformationEstimation2D< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimation3Point< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::ESFEstimation< PointInT, PointOutT >::scale_points_unit_sphere(), and pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::sgurf().

◆ determinant3x3Matrix()

template<typename Matrix >
Matrix::Scalar pcl::determinant3x3Matrix ( const Matrix &  matrix)
inline

#include <pcl/common/eigen.h>

Calculate the determinant of a 3x3 matrix.

Parameters
[in]matrixmatrix
Returns
determinant of the matrix

Definition at line 502 of file eigen.hpp.

◆ Div_Norm()

template<typename FloatVectorT >
float pcl::Div_Norm ( FloatVectorT  A,
FloatVectorT  B,
int  dim 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the div norm of the vector between two points.

Parameters
Athe first point
Bthe second point
dimthe number of dimensions in A and B (dimensions must match)
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 183 of file norms.hpp.

Referenced by pcl::selectNorm().

◆ eigen22() [1/2]

template<typename Matrix , typename Vector >
void pcl::eigen22 ( const Matrix &  mat,
Matrix &  eigenvectors,
Vector &  eigenvalues 
)
inline

#include <pcl/common/eigen.h>

determine the smallest eigenvalue and its corresponding eigenvector

Parameters
[in]matinput matrix that needs to be symmetric and positive semi definite
[out]eigenvectorsthe corresponding eigenvector to the smallest eigenvalue of the input matrix
[out]eigenvaluesthe smallest eigenvalue of the input matrix

Definition at line 172 of file eigen.hpp.

◆ eigen22() [2/2]

template<typename Matrix , typename Vector >
void pcl::eigen22 ( const Matrix &  mat,
typename Matrix::Scalar &  eigenvalue,
Vector &  eigenvector 
)
inline

#include <pcl/common/eigen.h>

determine the smallest eigenvalue and its corresponding eigenvector

Parameters
[in]matinput matrix that needs to be symmetric and positive semi definite
[out]eigenvaluethe smallest eigenvalue of the input matrix
[out]eigenvectorthe corresponding eigenvector to the smallest eigenvalue of the input matrix

Definition at line 133 of file eigen.hpp.

Referenced by pcl::approximatePolygon2D().

◆ eigen33() [1/3]

template<typename Matrix , typename Vector >
void pcl::eigen33 ( const Matrix &  mat,
Matrix &  evecs,
Vector &  evals 
)
inline

#include <pcl/common/eigen.h>

determines the eigenvalues and corresponding eigenvectors of the symmetric positive semi definite input matrix

Parameters
[in]matsymmetric positive semi definite input matrix
[out]evecscorresponding eigenvectors in correct order according to eigenvalues
[out]evalsresulting eigenvalues in ascending order

Definition at line 344 of file eigen.hpp.

References pcl::computeRoots(), and pcl::geometry::distance().

◆ eigen33() [2/3]

template<typename Matrix , typename Vector >
void pcl::eigen33 ( const Matrix &  mat,
typename Matrix::Scalar &  eigenvalue,
Vector &  eigenvector 
)
inline

#include <pcl/common/eigen.h>

determines the eigenvector and eigenvalue of the smallest eigenvalue of the symmetric positive semi definite input matrix

Parameters
[in]matsymmetric positive semi definite input matrix
[out]eigenvaluesmallest eigenvalue of the input matrix
[out]eigenvectorthe corresponding eigenvector for the input eigenvalue
Note
if the smallest eigenvalue is not unique, this function may return any eigenvector that is consistent to the eigenvalue.

Definition at line 295 of file eigen.hpp.

References pcl::computeRoots().

Referenced by pcl::gpu::people::buildTree(), pcl::ConvexHull< PointInT >::calculateInputDimension(), pcl::MLSResult::computeMLSSurface(), pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::computePointIntensityGradient(), pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::computePointNormal(), pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::computePointNormalMirror(), pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::computePointPrincipalCurvatures(), pcl::SampleConsensusModelRegistration< PointT >::computeSampleDistanceThreshold(), pcl::VectorAverage< real, dimension >::doPCA(), pcl::VectorAverage< real, dimension >::getEigenVector1(), pcl::getPrincipalTransformation(), pcl::GridProjection< PointNT >::getProjectionWithPlaneFit(), pcl::isPointIn2DPolygon(), pcl::SampleConsensusModelLine< PointT >::optimizeModelCoefficients(), pcl::SampleConsensusModelPlane< PointT >::optimizeModelCoefficients(), pcl::SampleConsensusModelStick< PointT >::optimizeModelCoefficients(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseTomasi(), pcl::ExtractPolygonalPrismData< PointT >::segment(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment(), pcl::solvePlaneParameters(), and pcl::gpu::people::label_skeleton::sortIndicesToBlob2().

◆ eigen33() [3/3]

template<typename Matrix , typename Vector >
void pcl::eigen33 ( const Matrix &  mat,
Vector &  evals 
)
inline

#include <pcl/common/eigen.h>

determines the eigenvalues of the symmetric positive semi definite input matrix

Parameters
[in]matsymmetric positive semi definite input matrix
[out]evalsresulting eigenvalues in ascending order

Definition at line 330 of file eigen.hpp.

References pcl::computeRoots().

◆ getAngle3D() [1/2]

double pcl::getAngle3D ( const Eigen::Vector3f &  v1,
const Eigen::Vector3f &  v2,
const bool  in_degree = false 
)
inline

#include <pcl/common/common.h>

Compute the smallest angle between two 3D vectors in radians (default) or degree.

Parameters
v1the first 3D vector (represented as a Eigen::Vector3f)
v2the second 3D vector (represented as a Eigen::Vector3f)
in_degreedetermine if angle should be in radians or degrees
Returns
the angle between v1 and v2 in radians or degrees

Definition at line 59 of file common.hpp.

References M_PI.

◆ getAngle3D() [2/2]

double pcl::getAngle3D ( const Eigen::Vector4f &  v1,
const Eigen::Vector4f &  v2,
const bool  in_degree = false 
)
inline

#include <pcl/common/common.h>

Compute the smallest angle between two 3D vectors in radians (default) or degree.

Parameters
v1the first 3D vector (represented as a Eigen::Vector4f)
v2the second 3D vector (represented as a Eigen::Vector4f)
in_degreedetermine if angle should be in radians or degrees
Returns
the angle between v1 and v2 in radians or degrees
Note
Handles rounding error for parallel and anti-parallel vectors

Definition at line 47 of file common.hpp.

References M_PI.

Referenced by pcl::tracking::NormalCoherence< PointInT >::computeCoherence(), pcl::tracking::ParticleFilterTracker< PointInT, StateT >::computeTransformedPointCloudWithNormal(), pcl::LCCPSegmentation< PointT >::connIsConvex(), pcl::SampleConsensusModelCone< PointT, PointNT >::countWithinDistance(), pcl::SampleConsensusModelCylinder< PointT, PointNT >::countWithinDistance(), pcl::SampleConsensusModelNormalSphere< PointT, PointNT >::countWithinDistance(), pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::countWithinDistanceStandard(), pcl::SampleConsensusModelCone< PointT, PointNT >::getDistancesToModel(), pcl::SampleConsensusModelCylinder< PointT, PointNT >::getDistancesToModel(), pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::getDistancesToModel(), pcl::SampleConsensusModelNormalSphere< PointT, PointNT >::getDistancesToModel(), pcl::SampleConsensusModelCone< PointT, PointNT >::isModelValid(), pcl::SampleConsensusModelCylinder< PointT, PointNT >::isModelValid(), pcl::SampleConsensusModelParallelLine< PointT >::isModelValid(), pcl::SampleConsensusModelPerpendicularPlane< PointT >::isModelValid(), pcl::SampleConsensusModelCone< PointT, PointNT >::selectWithinDistance(), pcl::SampleConsensusModelCylinder< PointT, PointNT >::selectWithinDistance(), pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::selectWithinDistance(), and pcl::SampleConsensusModelNormalSphere< PointT, PointNT >::selectWithinDistance().

◆ getCircumcircleRadius()

template<typename PointT >
double pcl::getCircumcircleRadius ( const PointT pa,
const PointT pb,
const PointT pc 
)
inline

#include <pcl/common/common.h>

Compute the radius of a circumscribed circle for a triangle formed of three points pa, pb, and pc.

Parameters
pathe first point
pbthe second point
pcthe third point
Returns
the radius of the circumscribed circle

Definition at line 383 of file common.hpp.

Referenced by pcl::ConcaveHull< PointInT >::performReconstruction().

◆ getEigenAsPointCloud()

PCL_EXPORTS bool pcl::getEigenAsPointCloud ( Eigen::MatrixXf &  in,
pcl::PCLPointCloud2 out 
)

#include <pcl/common/io.h>

Copy the XYZ dimensions from an Eigen MatrixXf into a pcl::PCLPointCloud2 message.

Parameters
[in]inthe Eigen MatrixXf format containing XYZ0 / point
[out]outthe resultant point cloud message
Note
the method assumes that the PCLPointCloud2 message already has the fields set up properly !

◆ getEulerAngles()

template<typename Scalar >
void pcl::getEulerAngles ( const Eigen::Transform< Scalar, 3, Eigen::Affine > &  t,
Scalar &  roll,
Scalar &  pitch,
Scalar &  yaw 
)

#include <pcl/common/eigen.h>

Extract the Euler angles (intrinsic rotations, ZYX-convention) from the given transformation.

Parameters
[in]tthe input transformation matrix
[in]rollthe resulting roll angle
[in]pitchthe resulting pitch angle
[in]yawthe resulting yaw angle

Definition at line 595 of file eigen.hpp.

Referenced by pcl::tracking::ParticleXYZRPY::sample().

◆ getFieldIndex() [1/3]

int pcl::getFieldIndex ( const pcl::PCLPointCloud2 cloud,
const std::string &  field_name 
)
inline

#include <pcl/common/io.h>

Get the index of a specified field (i.e., dimension/channel)

Parameters
[in]cloudthe point cloud message
[in]field_namethe string defining the field name
Returns
the index of the field or a negative integer if no field with the given name exists

Definition at line 61 of file io.h.

References pcl::geometry::distance(), and pcl::PCLPointCloud2::fields.

◆ getFieldIndex() [2/3]

template<typename PointT >
int pcl::getFieldIndex ( const std::string &  field_name,
const std::vector< pcl::PCLPointField > &  fields 
)

#include <pcl/common/impl/io.hpp>

Get the index of a specified field (i.e., dimension/channel)

Template Parameters
PointTdatatype for which fields is being queries
Parameters
[in]field_namethe string defining the field name
[in]fieldsa vector to the original PCLPointField vector that the raw PointCloud message contains

Definition at line 71 of file io.hpp.

References pcl::geometry::distance().

◆ getFieldIndex() [3/3]

template<typename PointT >
int pcl::getFieldIndex ( const std::string &  field_name,
std::vector< pcl::PCLPointField > &  fields 
)

#include <pcl/common/impl/io.hpp>

Get the index of a specified field (i.e., dimension/channel)

Template Parameters
PointTdatatype for which fields is being queries
Parameters
[in]field_namethe string defining the field name
[out]fieldsa vector to the original PCLPointField vector that the raw PointCloud message contains
Returns
the index of the field or a negative integer if no field with the given name exists

Definition at line 61 of file io.hpp.

◆ getFields()

template<typename PointT >
std::vector< pcl::PCLPointField > pcl::getFields ( )
inline

#include <pcl/common/impl/io.hpp>

Get the list of available fields (i.e., dimension/channel)

Template Parameters
PointTdatatype whose details are requested

Definition at line 97 of file io.hpp.

◆ getFieldSize()

int pcl::getFieldSize ( const int  datatype)
inline

◆ getFieldsList() [1/2]

std::string pcl::getFieldsList ( const pcl::PCLPointCloud2 cloud)
inline

#include <pcl/common/io.h>

Get the available point cloud fields as a space separated string.

Parameters
[in]clouda pointer to the PointCloud message

Definition at line 110 of file io.h.

References pcl::PCLPointCloud2::fields.

◆ getFieldsList() [2/2]

template<typename PointT >
std::string pcl::getFieldsList ( const pcl::PointCloud< PointT > &  cloud)
inline

#include <pcl/common/impl/io.hpp>

Get the list of all fields available in a given cloud.

Parameters
[in]cloudthe point cloud message

Definition at line 107 of file io.hpp.

◆ getFieldType() [1/2]

int pcl::getFieldType ( const int  size,
char  type 
)
inline

#include <pcl/common/io.h>

Obtains the type of the PCLPointField from a specific size and type.

Parameters
[in]sizethe size in bytes of the data field
[in]typea char describing the type of the field ('B' = bool, 'F' = float, 'I' = signed, 'U' = unsigned)

Definition at line 171 of file io.h.

References pcl::PCLPointField::BOOL, pcl::PCLPointField::FLOAT32, pcl::PCLPointField::FLOAT64, pcl::PCLPointField::INT16, pcl::PCLPointField::INT32, pcl::PCLPointField::INT64, pcl::PCLPointField::INT8, pcl::PCLPointField::UINT16, pcl::PCLPointField::UINT32, pcl::PCLPointField::UINT64, and pcl::PCLPointField::UINT8.

Referenced by pcl::PCDWriter::generateHeader().

◆ getFieldType() [2/2]

char pcl::getFieldType ( const int  type)
inline

◆ getMaxDistance() [1/2]

template<typename PointT >
void pcl::getMaxDistance ( const pcl::PointCloud< PointT > &  cloud,
const Eigen::Vector4f &  pivot_pt,
Eigen::Vector4f &  max_pt 
)
inline

#include <pcl/common/common.h>

Get the point at maximum distance from a given point and a given pointcloud.

Parameters
cloudthe point cloud data message
pivot_ptthe point from where to compute the distance
max_ptthe point in cloud that is the farthest point away from pivot_pt

Definition at line 197 of file common.hpp.

References pcl::PointCloud< PointT >::is_dense, and pcl::PointCloud< PointT >::size().

Referenced by pcl::GASDEstimation< PointInT, PointOutT >::computeFeature(), pcl::VFHEstimation< PointInT, PointNT, PointOutT >::computePointSPFHSignature(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::computeRFAndShapeDistribution(), and pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::sgurf().

◆ getMaxDistance() [2/2]

template<typename PointT >
void pcl::getMaxDistance ( const pcl::PointCloud< PointT > &  cloud,
const Indices indices,
const Eigen::Vector4f &  pivot_pt,
Eigen::Vector4f &  max_pt 
)
inline

#include <pcl/common/common.h>

Get the point at maximum distance from a given point and a given pointcloud.

Parameters
cloudthe point cloud data message
indicesthe vector of point indices to use from cloud
pivot_ptthe point from where to compute the distance
max_ptthe point in cloud that is the farthest point away from pivot_pt

Definition at line 244 of file common.hpp.

References pcl::PointCloud< PointT >::is_dense.

◆ getMaxSegment() [1/2]

template<typename PointT >
double pcl::getMaxSegment ( const pcl::PointCloud< PointT > &  cloud,
const Indices indices,
PointT pmin,
PointT pmax 
)
inline

#include <pcl/common/distances.h>

Obtain the maximum segment in a given set of points, and return the minimum and maximum points.

Parameters
[in]cloudthe point cloud dataset
[in]indicesa set of point indices to use from cloud
[out]pminthe coordinates of the "minimum" point in cloud (one end of the segment)
[out]pmaxthe coordinates of the "maximum" point in cloud (the other end of the segment)
Returns
the length of segment length

Definition at line 146 of file distances.h.

◆ getMaxSegment() [2/2]

template<typename PointT >
double pcl::getMaxSegment ( const pcl::PointCloud< PointT > &  cloud,
PointT pmin,
PointT pmax 
)
inline

#include <pcl/common/distances.h>

Obtain the maximum segment in a given set of points, and return the minimum and maximum points.

Parameters
[in]cloudthe point cloud dataset
[out]pminthe coordinates of the "minimum" point in cloud (one end of the segment)
[out]pmaxthe coordinates of the "maximum" point in cloud (the other end of the segment)
Returns
the length of segment length

Definition at line 106 of file distances.h.

References pcl::PointCloud< PointT >::size().

◆ getMeanStd()

void pcl::getMeanStd ( const std::vector< float > &  values,
double &  mean,
double &  stddev 
)
inline

#include <pcl/common/common.h>

Compute both the mean and the standard deviation of an array of values.

Parameters
valuesthe array of values
meanthe resultant mean of the distribution
stddevthe resultant standard deviation of the distribution

Definition at line 124 of file common.hpp.

◆ getMeanStdDev()

PCL_EXPORTS void pcl::getMeanStdDev ( const std::vector< float > &  values,
double &  mean,
double &  stddev 
)

#include <pcl/common/common.h>

Compute both the mean and the standard deviation of an array of values.

Parameters
valuesthe array of values
meanthe resultant mean of the distribution
stddevthe resultant standard deviation of the distribution

◆ getMinMax() [1/2]

PCL_EXPORTS void pcl::getMinMax ( const pcl::PCLPointCloud2 cloud,
int  idx,
const std::string &  field_name,
float &  min_p,
float &  max_p 
)

#include <pcl/common/common.h>

Get the minimum and maximum values on a point histogram.

Parameters
cloudthe cloud containing multi-dimensional histograms
idxpoint index representing the histogram that we need to compute min/max for
field_namethe field name containing the multi-dimensional histogram
min_pthe resultant minimum
max_pthe resultant maximum

◆ getMinMax() [2/2]

template<typename PointT >
void pcl::getMinMax ( const PointT histogram,
int  len,
float &  min_p,
float &  max_p 
)
inline

#include <pcl/common/common.h>

Get the minimum and maximum values on a point histogram.

Parameters
histogramthe point representing a multi-dimensional histogram
lenthe length of the histogram
min_pthe resultant minimum
max_pthe resultant maximum

Definition at line 400 of file common.hpp.

Referenced by pcl::MaximumLikelihoodSampleConsensus< PointT >::computeModel().

◆ getMinMax3D() [1/4]

template<typename PointT >
void pcl::getMinMax3D ( const pcl::PointCloud< PointT > &  cloud,
const Indices indices,
Eigen::Vector4f &  min_pt,
Eigen::Vector4f &  max_pt 
)
inline

#include <pcl/common/common.h>

Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.

Parameters
[in]cloudthe point cloud data message
[in]indicesthe vector of point indices to use from cloud
[out]min_ptthe resultant minimum bounds
[out]max_ptthe resultant maximum bounds

Definition at line 348 of file common.hpp.

References pcl::PointCloud< PointT >::is_dense.

◆ getMinMax3D() [2/4]

template<typename PointT >
void pcl::getMinMax3D ( const pcl::PointCloud< PointT > &  cloud,
const pcl::PointIndices indices,
Eigen::Vector4f &  min_pt,
Eigen::Vector4f &  max_pt 
)
inline

#include <pcl/common/common.h>

Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.

Parameters
[in]cloudthe point cloud data message
[in]indicesthe vector of point indices to use from cloud
[out]min_ptthe resultant minimum bounds
[out]max_ptthe resultant maximum bounds

Definition at line 340 of file common.hpp.

References pcl::getMinMax3D(), and pcl::PointIndices::indices.

◆ getMinMax3D() [3/4]

template<typename PointT >
void pcl::getMinMax3D ( const pcl::PointCloud< PointT > &  cloud,
Eigen::Vector4f &  min_pt,
Eigen::Vector4f &  max_pt 
)
inline

#include <pcl/common/common.h>

Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.

Parameters
[in]cloudthe point cloud data message
[out]min_ptthe resultant minimum bounds
[out]max_ptthe resultant maximum bounds

Definition at line 305 of file common.hpp.

References pcl::PointCloud< PointT >::is_dense, and pcl::PointCloud< PointT >::points.

◆ getMinMax3D() [4/4]

template<typename PointT >
void pcl::getMinMax3D ( const pcl::PointCloud< PointT > &  cloud,
PointT min_pt,
PointT max_pt 
)
inline

◆ getPointCloudAsEigen()

PCL_EXPORTS bool pcl::getPointCloudAsEigen ( const pcl::PCLPointCloud2 in,
Eigen::MatrixXf &  out 
)

#include <pcl/common/io.h>

Copy the XYZ dimensions of a pcl::PCLPointCloud2 into Eigen format.

Parameters
[in]inthe point cloud message
[out]outthe resultant Eigen MatrixXf format containing XYZ0 / point

◆ getPointsInBox()

template<typename PointT >
void pcl::getPointsInBox ( const pcl::PointCloud< PointT > &  cloud,
Eigen::Vector4f &  min_pt,
Eigen::Vector4f &  max_pt,
Indices indices 
)
inline

#include <pcl/common/common.h>

Get a set of points residing in a box given its bounds.

Parameters
cloudthe point cloud data message
min_ptthe minimum bounds
max_ptthe maximum bounds
indicesthe resultant set of point indices residing in the box

Definition at line 154 of file common.hpp.

References pcl::PointCloud< PointT >::is_dense, and pcl::PointCloud< PointT >::size().

Referenced by pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes().

◆ getTransformation() [1/2]

Eigen::Affine3f pcl::getTransformation ( float  x,
float  y,
float  z,
float  roll,
float  pitch,
float  yaw 
)
inline

#include <pcl/common/eigen.h>

Create a transformation from the given translation and Euler angles (intrinsic rotations, ZYX-convention)

Parameters
[in]xthe input x translation
[in]ythe input y translation
[in]zthe input z translation
[in]rollthe input roll angle
[in]pitchthe input pitch angle
[in]yawthe input yaw angle
Returns
the resulting transformation matrix

Definition at line 316 of file eigen.h.

◆ getTransformation() [2/2]

template<typename Scalar >
void pcl::getTransformation ( Scalar  x,
Scalar  y,
Scalar  z,
Scalar  roll,
Scalar  pitch,
Scalar  yaw,
Eigen::Transform< Scalar, 3, Eigen::Affine > &  t 
)

#include <pcl/common/eigen.h>

Create a transformation from the given translation and Euler angles (intrinsic rotations, ZYX-convention)

Parameters
[in]xthe input x translation
[in]ythe input y translation
[in]zthe input z translation
[in]rollthe input roll angle
[in]pitchthe input pitch angle
[in]yawthe input yaw angle
[out]tthe resulting transformation matrix

Definition at line 618 of file eigen.hpp.

References pcl::B.

Referenced by pcl::CropBox< PointT >::applyFilter(), pcl::registration::LUM< PointT >::computeEdge(), pcl::registration::LUM< PointT >::getConcatenatedCloud(), pcl::registration::LUM< PointT >::getTransformation(), pcl::registration::LUM< PointT >::getTransformedCloud(), pcl::tracking::ParticleXYZRPY::sample(), pcl::tracking::ParticleXYZRPY::toEigenMatrix(), pcl::tracking::ParticleXYZR::toEigenMatrix(), pcl::tracking::ParticleXYRPY::toEigenMatrix(), pcl::tracking::ParticleXYRP::toEigenMatrix(), and pcl::tracking::ParticleXYR::toEigenMatrix().

◆ getTransformationFromTwoUnitVectors() [1/2]

Eigen::Affine3f pcl::getTransformationFromTwoUnitVectors ( const Eigen::Vector3f &  y_direction,
const Eigen::Vector3f &  z_axis 
)
inline

#include <pcl/common/eigen.h>

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)

Parameters
[in]y_directionthe y direction
[in]z_axisthe z-axis
Returns
transformation the resultant 3D rotation

Definition at line 573 of file eigen.hpp.

References pcl::getTransformationFromTwoUnitVectors().

◆ getTransformationFromTwoUnitVectors() [2/2]

void pcl::getTransformationFromTwoUnitVectors ( const Eigen::Vector3f &  y_direction,
const Eigen::Vector3f &  z_axis,
Eigen::Affine3f &  transformation 
)
inline

#include <pcl/common/eigen.h>

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)

Parameters
[in]y_directionthe y direction
[in]z_axisthe z-axis
[out]transformationthe resultant 3D rotation

Definition at line 564 of file eigen.hpp.

References pcl::getTransFromUnitVectorsZY().

Referenced by pcl::RangeImage::getRotationToViewerCoordinateFrame(), pcl::getTransformationFromTwoUnitVectors(), and pcl::getTransformationFromTwoUnitVectorsAndOrigin().

◆ getTransformationFromTwoUnitVectorsAndOrigin()

void pcl::getTransformationFromTwoUnitVectorsAndOrigin ( const Eigen::Vector3f &  y_direction,
const Eigen::Vector3f &  z_axis,
const Eigen::Vector3f &  origin,
Eigen::Affine3f &  transformation 
)
inline

#include <pcl/common/eigen.h>

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)

Parameters
[in]y_directionthe y direction
[in]z_axisthe z-axis
[in]originthe origin
[in]transformationthe resultant transformation matrix

Definition at line 583 of file eigen.hpp.

References pcl::getTransformationFromTwoUnitVectors().

Referenced by pcl::RangeImage::getTransformationToViewerCoordinateFrame().

◆ getTransFromUnitVectorsXY() [1/2]

Eigen::Affine3f pcl::getTransFromUnitVectorsXY ( const Eigen::Vector3f &  x_axis,
const Eigen::Vector3f &  y_direction 
)
inline

#include <pcl/common/eigen.h>

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)

Parameters
[in]x_axisthe x-axis
[in]y_directionthe y direction
Returns
the resulting 3D rotation

Definition at line 554 of file eigen.hpp.

References pcl::getTransFromUnitVectorsXY().

◆ getTransFromUnitVectorsXY() [2/2]

void pcl::getTransFromUnitVectorsXY ( const Eigen::Vector3f &  x_axis,
const Eigen::Vector3f &  y_direction,
Eigen::Affine3f &  transformation 
)
inline

#include <pcl/common/eigen.h>

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)

Parameters
[in]x_axisthe x-axis
[in]y_directionthe y direction
[out]transformationthe resultant 3D rotation

Definition at line 538 of file eigen.hpp.

Referenced by pcl::getTransFromUnitVectorsXY().

◆ getTransFromUnitVectorsZY() [1/2]

Eigen::Affine3f pcl::getTransFromUnitVectorsZY ( const Eigen::Vector3f &  z_axis,
const Eigen::Vector3f &  y_direction 
)
inline

#include <pcl/common/eigen.h>

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)

Parameters
[in]z_axisthe z-axis
[in]y_directionthe y direction
Returns
the resultant 3D rotation

Definition at line 528 of file eigen.hpp.

References pcl::getTransFromUnitVectorsZY().

◆ getTransFromUnitVectorsZY() [2/2]

void pcl::getTransFromUnitVectorsZY ( const Eigen::Vector3f &  z_axis,
const Eigen::Vector3f &  y_direction,
Eigen::Affine3f &  transformation 
)
inline

#include <pcl/common/eigen.h>

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)

Parameters
[in]z_axisthe z-axis
[in]y_directionthe y direction
[out]transformationthe resultant 3D rotation

Definition at line 512 of file eigen.hpp.

Referenced by pcl::getTransformationFromTwoUnitVectors(), and pcl::getTransFromUnitVectorsZY().

◆ getTranslationAndEulerAngles()

template<typename Scalar >
void pcl::getTranslationAndEulerAngles ( const Eigen::Transform< Scalar, 3, Eigen::Affine > &  t,
Scalar &  x,
Scalar &  y,
Scalar &  z,
Scalar &  roll,
Scalar &  pitch,
Scalar &  yaw 
)

#include <pcl/common/eigen.h>

Extract x,y,z and the Euler angles (intrinsic rotations, ZYX-convention) from the given transformation.

Parameters
[in]tthe input transformation matrix
[out]xthe resulting x translation
[out]ythe resulting y translation
[out]zthe resulting z translation
[out]rollthe resulting roll angle
[out]pitchthe resulting pitch angle
[out]yawthe resulting yaw angle

Definition at line 604 of file eigen.hpp.

Referenced by pcl::Narf::copyToNarf36(), pcl::tracking::ParticleXYZRPY::toState(), pcl::tracking::ParticleXYZR::toState(), pcl::tracking::ParticleXYRPY::toState(), pcl::tracking::ParticleXYRP::toState(), and pcl::tracking::ParticleXYR::toState().

◆ HIK_Norm()

template<typename FloatVectorT >
float pcl::HIK_Norm ( FloatVectorT  A,
FloatVectorT  B,
int  dim 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the HIK norm of the vector between two points.

Parameters
Athe first point
Bthe second point
dimthe number of dimensions in A and B (dimensions must match)
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 233 of file norms.hpp.

Referenced by pcl::selectNorm().

◆ invert2x2()

template<typename Matrix >
Matrix::Scalar pcl::invert2x2 ( const Matrix &  matrix,
Matrix &  inverse 
)
inline

#include <pcl/common/eigen.h>

Calculate the inverse of a 2x2 matrix.

Parameters
[in]matrixmatrix to be inverted
[out]inversethe resultant inverted matrix
Note
only the upper triangular part is taken into account => non symmetric matrices will give wrong results
Returns
determinant of the original matrix => if 0 no inverse exists => result is invalid

Definition at line 415 of file eigen.hpp.

◆ invert3x3Matrix()

template<typename Matrix >
Matrix::Scalar pcl::invert3x3Matrix ( const Matrix &  matrix,
Matrix &  inverse 
)
inline

#include <pcl/common/eigen.h>

Calculate the inverse of a general 3x3 matrix.

Parameters
[in]matrixmatrix to be inverted
[out]inversethe resultant inverted matrix
Returns
determinant of the original matrix => if 0 no inverse exists => result is invalid

Definition at line 469 of file eigen.hpp.

◆ invert3x3SymMatrix()

template<typename Matrix >
Matrix::Scalar pcl::invert3x3SymMatrix ( const Matrix &  matrix,
Matrix &  inverse 
)
inline

#include <pcl/common/eigen.h>

Calculate the inverse of a 3x3 symmetric matrix.

Parameters
[in]matrixmatrix to be inverted
[out]inversethe resultant inverted matrix
Note
only the upper triangular part is taken into account => non symmetric matrices will give wrong results
Returns
determinant of the original matrix => if 0 no inverse exists => result is invalid

Definition at line 434 of file eigen.hpp.

◆ isBetterCorrespondence()

bool pcl::isBetterCorrespondence ( const Correspondence pc1,
const Correspondence pc2 
)
inline

#include <pcl/correspondence.h>

Comparator to enable us to sort a vector of PointCorrespondences according to their scores using std::sort (begin(), end(), isBetterCorrespondence);.

Definition at line 146 of file correspondence.h.

References pcl::Correspondence::distance.

◆ JM_Norm()

template<typename FloatVectorT >
float pcl::JM_Norm ( FloatVectorT  A,
FloatVectorT  B,
int  dim 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the JM norm of the vector between two points.

Parameters
Athe first point
Bthe second point
dimthe number of dimensions in A and B (dimensions must match)
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 128 of file norms.hpp.

Referenced by pcl::selectNorm().

◆ K_Norm()

template<typename FloatVectorT >
float pcl::K_Norm ( FloatVectorT  A,
FloatVectorT  B,
int  dim,
float  P1,
float  P2 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the K norm of the vector between two points.

Parameters
Athe first point
Bthe second point
dimthe number of dimensions in A and B (dimensions must match)
P1the first parameter
P2the second parameter
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 208 of file norms.hpp.

◆ KL_Norm()

template<typename FloatVectorT >
float pcl::KL_Norm ( FloatVectorT  A,
FloatVectorT  B,
int  dim 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the KL between two discrete probability density functions.

Parameters
Athe first discrete PDF
Bthe second discrete PDF
dimthe number of dimensions in A and B (dimensions must match)
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 219 of file norms.hpp.

Referenced by pcl::selectNorm().

◆ L1_Norm()

template<typename FloatVectorT >
float pcl::L1_Norm ( FloatVectorT  A,
FloatVectorT  B,
int  dim 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the L1 norm of the vector between two points.

Parameters
Athe first point
Bthe second point
dimthe number of dimensions in A and B (dimensions must match)
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 88 of file norms.hpp.

Referenced by pcl::Narf::getDescriptorDistance(), and pcl::selectNorm().

◆ L2_Norm()

template<typename FloatVectorT >
float pcl::L2_Norm ( FloatVectorT  A,
FloatVectorT  B,
int  dim 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the L2 norm of the vector between two points.

Parameters
Athe first point
Bthe second point
dimthe number of dimensions in A and B (dimensions must match)
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 111 of file norms.hpp.

References pcl::L2_Norm_SQR().

Referenced by pcl::selectNorm().

◆ L2_Norm_SQR()

template<typename FloatVectorT >
float pcl::L2_Norm_SQR ( FloatVectorT  A,
FloatVectorT  B,
int  dim 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the squared L2 norm of the vector between two points.

Parameters
Athe first point
Bthe second point
dimthe number of dimensions in A and B (dimensions must match)
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 98 of file norms.hpp.

Referenced by pcl::L2_Norm(), and pcl::selectNorm().

◆ lineToLineSegment()

PCL_EXPORTS void pcl::lineToLineSegment ( const Eigen::VectorXf &  line_a,
const Eigen::VectorXf &  line_b,
Eigen::Vector4f &  pt1_seg,
Eigen::Vector4f &  pt2_seg 
)

#include <pcl/common/distances.h>

Get the shortest 3D segment between two 3D lines.

Parameters
line_athe coefficients of the first line (point, direction)
line_bthe coefficients of the second line (point, direction)
pt1_segthe first point on the line segment
pt2_segthe second point on the line segment

Referenced by pcl::lineWithLineIntersection().

◆ lineWithLineIntersection() [1/2]

PCL_EXPORTS bool pcl::lineWithLineIntersection ( const Eigen::VectorXf &  line_a,
const Eigen::VectorXf &  line_b,
Eigen::Vector4f &  point,
double  sqr_eps = 1e-4 
)
inline

#include <pcl/common/impl/intersections.hpp>

Get the intersection of a two 3D lines in space as a 3D point.

Parameters
[in]line_athe coefficients of the first line (point, direction)
[in]line_bthe coefficients of the second line (point, direction)
[out]pointholder for the computed 3D point
[in]sqr_epsmaximum allowable squared distance to the true solution

Definition at line 49 of file intersections.hpp.

References pcl::lineToLineSegment().

Referenced by pcl::lineWithLineIntersection().

◆ lineWithLineIntersection() [2/2]

PCL_EXPORTS bool pcl::lineWithLineIntersection ( const pcl::ModelCoefficients line_a,
const pcl::ModelCoefficients line_b,
Eigen::Vector4f &  point,
double  sqr_eps = 1e-4 
)
inline

#include <pcl/common/impl/intersections.hpp>

Get the intersection of a two 3D lines in space as a 3D point.

Parameters
[in]line_athe coefficients of the first line (point, direction)
[in]line_bthe coefficients of the second line (point, direction)
[out]pointholder for the computed 3D point
[in]sqr_epsmaximum allowable squared distance to the true solution

Definition at line 69 of file intersections.hpp.

References pcl::lineWithLineIntersection(), and pcl::ModelCoefficients::values.

◆ Linf_Norm()

template<typename FloatVectorT >
float pcl::Linf_Norm ( FloatVectorT  A,
FloatVectorT  B,
int  dim 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the L-infinity norm of the vector between two points.

Parameters
Athe first point
Bthe second point
dimthe number of dimensions in A and B (dimensions must match)
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 118 of file norms.hpp.

Referenced by pcl::selectNorm().

◆ loadBinary()

template<typename Derived >
void pcl::loadBinary ( Eigen::MatrixBase< Derived > const &  matrix,
std::istream &  file 
)

#include <pcl/common/eigen.h>

Read a matrix from an input stream.

Parameters
[out]matrixthe resulting matrix, read from the input stream
[in,out]filethe input stream

Definition at line 648 of file eigen.hpp.

◆ normAngle()

float pcl::normAngle ( float  alpha)
inline

#include <pcl/common/angles.h>

Normalize an angle to (-PI, PI].

Parameters
alphathe input angle (in radians)

Definition at line 48 of file angles.hpp.

References M_PI.

◆ PF_Norm()

template<typename FloatVectorT >
float pcl::PF_Norm ( FloatVectorT  A,
FloatVectorT  B,
int  dim,
float  P1,
float  P2 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the PF norm of the vector between two points.

Parameters
Athe first point
Bthe second point
dimthe number of dimensions in A and B (dimensions must match)
P1the first parameter
P2the second parameter
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 197 of file norms.hpp.

◆ rad2deg() [1/2]

double pcl::rad2deg ( double  alpha)
inline

#include <pcl/common/angles.h>

Convert an angle from radians to degrees.

Parameters
alphathe input angle (in radians)

Definition at line 73 of file angles.hpp.

◆ rad2deg() [2/2]

float pcl::rad2deg ( float  alpha)
inline

◆ saveBinary()

template<typename Derived >
void pcl::saveBinary ( const Eigen::MatrixBase< Derived > &  matrix,
std::ostream &  file 
)

#include <pcl/common/eigen.h>

Write a matrix to an output stream.

Parameters
[in]matrixthe matrix to output
[out]filethe output stream

Definition at line 633 of file eigen.hpp.

◆ selectNorm()

template<typename FloatVectorT >
float pcl::selectNorm ( FloatVectorT  A,
FloatVectorT  B,
int  dim,
NormType  norm_type 
)
inline

#include <pcl/common/impl/norms.hpp>

Method that calculates any norm type available, based on the norm_type variable.

Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 50 of file norms.hpp.

References pcl::B, pcl::B_Norm(), pcl::CS, pcl::CS_Norm(), pcl::DIV, pcl::Div_Norm(), pcl::HIK, pcl::HIK_Norm(), pcl::JM, pcl::JM_Norm(), pcl::K, pcl::KL, pcl::KL_Norm(), pcl::L1, pcl::L1_Norm(), pcl::L2, pcl::L2_Norm(), pcl::L2_Norm_SQR(), pcl::L2_SQR, pcl::LINF, pcl::Linf_Norm(), pcl::PF, pcl::SUBLINEAR, and pcl::Sublinear_Norm().

◆ sqrPointToLineDistance() [1/2]

double pcl::sqrPointToLineDistance ( const Eigen::Vector4f &  pt,
const Eigen::Vector4f &  line_pt,
const Eigen::Vector4f &  line_dir 
)
inline

#include <pcl/common/distances.h>

Get the square distance from a point to a line (represented by a point and a direction)

Parameters
pta point
line_pta point on the line (make sure that line_pt[3] = 0 as there are no internal checks!)
line_dirthe line direction

Definition at line 75 of file distances.h.

Referenced by pcl::SampleConsensusModelCylinder< PointT, PointNT >::computeModelCoefficients(), pcl::SampleConsensusModelCone< PointT, PointNT >::pointToAxisDistance(), and pcl::SampleConsensusModelCylinder< PointT, PointNT >::pointToLineDistance().

◆ sqrPointToLineDistance() [2/2]

double pcl::sqrPointToLineDistance ( const Eigen::Vector4f &  pt,
const Eigen::Vector4f &  line_pt,
const Eigen::Vector4f &  line_dir,
const double  sqr_length 
)
inline

#include <pcl/common/distances.h>

Get the square distance from a point to a line (represented by a point and a direction)

Note
This one is useful if one has to compute many distances to a fixed line, so the vector length can be pre-computed
Parameters
pta point
line_pta point on the line (make sure that line_pt[3] = 0 as there are no internal checks!)
line_dirthe line direction
sqr_lengththe squared norm of the line direction

Definition at line 91 of file distances.h.

◆ Sublinear_Norm()

template<typename FloatVectorT >
float pcl::Sublinear_Norm ( FloatVectorT  A,
FloatVectorT  B,
int  dim 
)
inline

#include <pcl/common/impl/norms.hpp>

Compute the sublinear norm of the vector between two points.

Parameters
Athe first point
Bthe second point
dimthe number of dimensions in A and B (dimensions must match)
Note
FloatVectorT is any type of vector with its values accessible via [ ]

Definition at line 157 of file norms.hpp.

Referenced by pcl::selectNorm().

◆ swapByte()

template<std::size_t N>
void pcl::io::swapByte ( char *  bytes)

#include <pcl/common/io.h>

swap bytes order of a char array of length N

Parameters
byteschar array to swap

◆ transformPoint()

template<typename PointT , typename Scalar >
PointT pcl::transformPoint ( const PointT point,
const Eigen::Transform< Scalar, 3, Eigen::Affine > &  transform 
)
inline

#include <pcl/common/impl/transforms.hpp>

Transform a point with members x,y,z.

Parameters
[in]pointthe point to transform
[out]transformthe transformation to apply
Returns
the transformed point

Definition at line 474 of file transforms.hpp.

References pcl::detail::Transformer< Scalar >::se3().

◆ transformPointCloud() [1/8]

void pcl::transformPointCloud ( const pcl::PointCloud< pcl::PointXY > &  cloud_in,
pcl::PointCloud< pcl::PointXY > &  cloud_out,
const Eigen::Affine2f &  transform,
bool  copy_all_fields = true 
)
inline

#include <pcl/common/impl/transforms.hpp>

Apply an affine transform on a pointcloud having points of type PointXY.

Parameters
[in]cloud_inthe input point cloud
[out]cloud_outthe resultant output point cloud
[in]transforman affine transformation
[in]copy_all_fieldsflag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud

Definition at line 310 of file transforms.hpp.

References pcl::PointCloud< PointT >::assign(), pcl::PointCloud< PointT >::begin(), pcl::PointCloud< PointT >::end(), pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::reserve(), pcl::PointCloud< PointT >::resize(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.

◆ transformPointCloud() [2/8]

template<typename PointT , typename Scalar >
void pcl::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 
)

#include <pcl/common/impl/transforms.hpp>

Apply a rigid transform defined by a 4x4 matrix.

Parameters
[in]cloud_inthe input point cloud
[in]indicesthe set of point indices to use from the input point cloud
[out]cloud_outthe resultant output point cloud
[in]transforma rigid transformation
[in]copy_all_fieldsflag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud

Definition at line 263 of file transforms.hpp.

References pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::resize(), pcl::detail::Transformer< Scalar >::se3(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, and pcl::PointCloud< PointT >::width.

◆ transformPointCloud() [3/8]

template<typename PointT , typename Scalar >
void pcl::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 
)

#include <pcl/common/transforms.h>

Apply an affine transform defined by an Eigen Transform.

Parameters
[in]cloud_inthe input point cloud
[in]indicesthe set of point indices to use from the input point cloud
[out]cloud_outthe resultant output point cloud
[in]transforman affine transformation (typically a rigid transformation)
[in]copy_all_fieldsflag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud

Definition at line 86 of file transforms.h.

◆ transformPointCloud() [4/8]

template<typename PointT , typename Scalar >
void pcl::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 
)

#include <pcl/common/transforms.h>

Apply a rigid transform defined by a 4x4 matrix.

Parameters
[in]cloud_inthe input point cloud
[in]indicesthe set of point indices to use from the input point cloud
[out]cloud_outthe resultant output point cloud
[in]transforma rigid transformation
[in]copy_all_fieldsflag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud

Definition at line 280 of file transforms.h.

References pcl::PointIndices::indices.

◆ transformPointCloud() [5/8]

template<typename PointT , typename Scalar >
void pcl::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 
)

#include <pcl/common/transforms.h>

Apply an affine transform defined by an Eigen Transform.

Parameters
[in]cloud_inthe input point cloud
[in]indicesthe set of point indices to use from the input point cloud
[out]cloud_outthe resultant output point cloud
[in]transforman affine transformation (typically a rigid transformation)
[in]copy_all_fieldsflag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud

Definition at line 115 of file transforms.h.

References pcl::PointIndices::indices.

◆ transformPointCloud() [6/8]

template<typename PointT , typename Scalar >
void pcl::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 
)
inline

#include <pcl/common/impl/transforms.hpp>

Apply a rigid transform defined by a 3D offset and a quaternion.

Parameters
[in]cloud_inthe input point cloud
[out]cloud_outthe resultant output point cloud
[in]offsetthe translation component of the rigid transformation
[in]rotationthe rotation component of the rigid transformation
[in]copy_all_fieldsflag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud

Definition at line 446 of file transforms.hpp.

References pcl::transformPointCloud().

◆ transformPointCloud() [7/8]

template<typename PointT , typename Scalar >
void pcl::transformPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
pcl::PointCloud< PointT > &  cloud_out,
const Eigen::Matrix< Scalar, 4, 4 > &  transform,
bool  copy_all_fields = true 
)

#include <pcl/common/impl/transforms.hpp>

Apply a rigid transform defined by a 4x4 matrix.

Parameters
[in]cloud_inthe input point cloud
[out]cloud_outthe resultant output point cloud
[in]transforma rigid transformation
[in]copy_all_fieldsflag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud
Note
Can be used with cloud_in equal to cloud_out

Definition at line 221 of file transforms.hpp.

References pcl::PointCloud< PointT >::assign(), pcl::PointCloud< PointT >::begin(), pcl::PointCloud< PointT >::data(), pcl::PointCloud< PointT >::end(), pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::reserve(), pcl::PointCloud< PointT >::resize(), pcl::detail::Transformer< Scalar >::se3(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.

Referenced by ObjectRecognition::alignModelPoints(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::applyTransformationPointCloud(), pcl::registration::ELCH< PointT >::compute(), pcl::GASDEstimation< PointInT, PointOutT >::computeFeature(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::computeRFAndShapeDistribution(), pcl::NormalDistributionsTransform< PointSource, PointTarget, Scalar >::computeStepLengthMT(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::computeTransformation(), pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::computeTransformation(), pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::computeTransformation(), pcl::SampleConsensusPrerejective< PointSource, PointTarget, FeatureT >::computeTransformation(), pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget, Scalar >::computeTransformation(), pcl::NormalDistributionsTransform< PointSource, PointTarget, Scalar >::computeTransformation(), pcl::registration::LUM< PointT >::getConcatenatedCloud(), pcl::kinfuLS::WorldModel< pcl::PointXYZI >::getExistingData(), pcl::SampleConsensusPrerejective< PointSource, PointTarget, FeatureT >::getFitness(), pcl::Registration< PointSource, PointTarget, Scalar >::getFitnessScore(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::getMeshesFromTSDFVector(), pcl::registration::LUM< PointT >::getTransformedCloud(), pcl::TextureMapping< PointInT >::mapMultipleTexturesToMeshUV(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::registration::MetaRegistration< PointT, Scalar >::registerCloud(), pcl::ESFEstimation< PointInT, PointOutT >::scale_points_unit_sphere(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::sgurf(), pcl::TextureMapping< PointInT >::sortFacesByCamera(), pcl::TextureMapping< PointInT >::textureMeshwithMultipleCameras(), pcl::transformPointCloud(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateMatch(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateTransformation(), and pcl::registration::KFPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateTransformation().

◆ transformPointCloud() [8/8]

template<typename PointT , typename Scalar >
void pcl::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 
)

#include <pcl/common/transforms.h>

Apply an affine transform defined by an Eigen Transform.

Parameters
[in]cloud_inthe input point cloud
[out]cloud_outthe resultant output point cloud
[in]transforman affine transformation (typically a rigid transformation)
[in]copy_all_fieldsflag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud
Note
Can be used with cloud_in equal to cloud_out

Definition at line 59 of file transforms.h.

◆ transformPointCloudWithNormals() [1/4]

template<typename PointT , typename Scalar >
void pcl::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 
)

#include <pcl/common/impl/transforms.hpp>

Transform a point cloud and rotate its normals using an Eigen transform.

Parameters
[in]cloud_inthe input point cloud
[in]indicesthe set of point indices to use from the input point cloud
[out]cloud_outthe resultant output point cloud
[in]transforman affine transformation (typically a rigid transformation)
[in]copy_all_fieldsflag 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
Note
Can be used with cloud_in equal to cloud_out

Definition at line 395 of file transforms.hpp.

References pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::resize(), pcl::detail::Transformer< Scalar >::se3(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), pcl::detail::Transformer< Scalar >::so3(), and pcl::PointCloud< PointT >::width.

◆ transformPointCloudWithNormals() [2/4]

template<typename PointT , typename Scalar >
void pcl::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 
)

#include <pcl/common/transforms.h>

Transform a point cloud and rotate its normals using an Eigen transform.

Parameters
[in]cloud_inthe input point cloud
[in]indicesthe set of point indices to use from the input point cloud
[out]cloud_outthe resultant output point cloud
[in]transforman affine transformation (typically a rigid transformation)
[in]copy_all_fieldsflag 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
Note
Can be used with cloud_in equal to cloud_out

Definition at line 366 of file transforms.h.

References pcl::PointIndices::indices.

◆ transformPointCloudWithNormals() [3/4]

template<typename PointT , typename Scalar >
void pcl::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 
)
inline

#include <pcl/common/impl/transforms.hpp>

Transform a point cloud and rotate its normals using an Eigen transform.

Parameters
[in]cloud_inthe input point cloud
[out]cloud_outthe resultant output point cloud
[in]offsetthe translation component of the rigid transformation
[in]rotationthe rotation component of the rigid transformation
[in]copy_all_fieldsflag 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 460 of file transforms.hpp.

References pcl::transformPointCloudWithNormals().

◆ transformPointCloudWithNormals() [4/4]

template<typename PointT , typename Scalar >
void pcl::transformPointCloudWithNormals ( const pcl::PointCloud< PointT > &  cloud_in,
pcl::PointCloud< PointT > &  cloud_out,
const Eigen::Matrix< Scalar, 4, 4 > &  transform,
bool  copy_all_fields = true 
)

#include <pcl/common/impl/transforms.hpp>

Transform a point cloud and rotate its normals using an Eigen transform.

Parameters
[in]cloud_inthe input point cloud
[out]cloud_outthe resultant output point cloud
[in]transforman affine transformation (typically a rigid transformation)
[in]copy_all_fieldsflag 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
Note
Can be used with cloud_in equal to cloud_out

Definition at line 349 of file transforms.hpp.

References pcl::PointCloud< PointT >::assign(), pcl::PointCloud< PointT >::begin(), pcl::PointCloud< PointT >::end(), pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::reserve(), pcl::PointCloud< PointT >::resize(), pcl::detail::Transformer< Scalar >::se3(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), pcl::detail::Transformer< Scalar >::so3(), and pcl::PointCloud< PointT >::width.

Referenced by pcl::IterativeClosestPointWithNormals< PointSource, PointTarget, Scalar >::transformCloud(), and pcl::transformPointCloudWithNormals().

◆ transformPointWithNormal()

template<typename PointT , typename Scalar >
PointT pcl::transformPointWithNormal ( const PointT point,
const Eigen::Transform< Scalar, 3, Eigen::Affine > &  transform 
)
inline

#include <pcl/common/impl/transforms.hpp>

Transform a point with members x,y,z,normal_x,normal_y,normal_z.

Parameters
[in]pointthe point to transform
[out]transformthe transformation to apply
Returns
the transformed point

Definition at line 484 of file transforms.hpp.

References pcl::detail::Transformer< Scalar >::se3(), and pcl::detail::Transformer< Scalar >::so3().