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.
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 |
file | centroid.h |
file | common.h |
file | distances.h |
file | file_io.h |
file | random.h |
CloudGenerator class generates a point cloud using some randoom number generator. |
|
file | geometry.h |
file | intersections.h |
file | norms.h |
file | geometry.h |
file | time.h |
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 |
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 > ¢roid) |
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 > ¢roid) |
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 > ¢roid) |
Compute the 3D (X-Y-Z) centroid of a set of points using their indices and return it as a 3D vector. More... |
|
template<typename PointT , typename Scalar > | |
unsigned int | pcl::compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix< Scalar, 4, 1 > ¢roid) |
Compute the 3D (X-Y-Z) centroid of a set of points using their indices and return it as a 3D vector. More... |
|
template<typename PointT , typename Scalar > | |
unsigned int | pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the 3x3 covariance matrix of a given set of points. More... |
|
template<typename PointT , typename Scalar > | |
unsigned int | pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute normalized the 3x3 covariance matrix of a given set of points. More... |
|
template<typename PointT , typename Scalar > | |
unsigned int | pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Indices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the 3x3 covariance matrix of a given set of points using their indices. More... |
|
template<typename PointT , typename Scalar > | |
unsigned int | pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the 3x3 covariance matrix of a given set of points using their indices. More... |
|
template<typename PointT , typename Scalar > | |
unsigned int | pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const Indices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the normalized 3x3 covariance matrix of a given set of points using their indices. More... |
|
template<typename PointT , typename Scalar > | |
unsigned int | pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix) |
Compute the normalized 3x3 covariance matrix of a given set of points using their indices. More... |
|
template<typename PointT , typename Scalar > | |
unsigned int | pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix, Eigen::Matrix< Scalar, 4, 1 > ¢roid) |
Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. More... |
|
template<typename PointT , 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 > ¢roid) |
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 > ¢roid) |
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 > | |
void | pcl::demeanPointCloud (ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, pcl::PointCloud< PointT > &cloud_out, int npts=0) |
Subtract a centroid from a point cloud and return the de-meaned representation. More... |
|
template<typename PointT , typename Scalar > | |
void | pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, pcl::PointCloud< PointT > &cloud_out) |
Subtract a centroid from a point cloud and return the de-meaned representation. More... |
|
template<typename PointT , typename Scalar > | |
void | pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, pcl::PointCloud< PointT > &cloud_out) |
Subtract a centroid from a point cloud and return the de-meaned representation. More... |
|
template<typename PointT , typename Scalar > | |
void | pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, pcl::PointCloud< PointT > &cloud_out) |
Subtract a centroid from a point cloud and return the de-meaned representation. More... |
|
template<typename PointT , typename Scalar > | |
void | pcl::demeanPointCloud (ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > &cloud_out, int npts=0) |
Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix. More... |
|
template<typename PointT , typename Scalar > | |
void | pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > &cloud_out) |
Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix. More... |
|
template<typename PointT , typename Scalar > | |
void | pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Indices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > &cloud_out) |
Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix. More... |
|
template<typename PointT , typename Scalar > | |
void | pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > &cloud_out) |
Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix. More... |
|
template<typename PointT , typename Scalar > | |
void | pcl::computeNDCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > ¢roid) |
General, all purpose nD centroid estimation for a set of points using their indices. More... |
|
template<typename PointT , typename Scalar > | |
void | pcl::computeNDCentroid (const pcl::PointCloud< PointT > &cloud, const Indices &indices, Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > ¢roid) |
General, all purpose nD centroid estimation for a set of points using their indices. More... |
|
template<typename PointT , typename Scalar > | |
void | pcl::computeNDCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > ¢roid) |
General, all purpose nD centroid estimation for a set of points using their indices. More... |
|
template<typename PointInT , typename PointOutT > | |
std::size_t | pcl::computeCentroid (const pcl::PointCloud< PointInT > &cloud, PointOutT ¢roid) |
Compute the centroid of a set of points and return it as a point. More... |
|
template<typename PointInT , typename PointOutT > | |
std::size_t | pcl::computeCentroid (const pcl::PointCloud< PointInT > &cloud, const Indices &indices, PointOutT ¢roid) |
Compute the centroid of a set of points and return it as a point. More... |
|
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::PCLPointField > | pcl::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... |
|
#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.
#define PCL_MAKE_ALIGNED_OPERATOR_NEW |
#include <pcl/memory.h>
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
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.
enum pcl::BorderTrait |
#include <pcl/point_types.h>
Specification of the fields for BorderDescription::traits.
Definition at line 312 of file point_types.h.
enum pcl::NormType |
#include <pcl/common/norms.h>
Enum that defines all the types of norms available.
Enumerator | |
---|---|
L1 | |
L2_SQR | |
L2 | |
LINF | |
JM | |
B | |
SUBLINEAR | |
CS | |
DIV | |
PF | |
K | |
KL | |
HIK |
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the B norm of the vector between two points.
A | the first point |
B | the second point |
dim | the number of dimensions in A and B (dimensions must match) |
Definition at line 140 of file norms.hpp.
Referenced by pcl::selectNorm().
| inline |
#include <pcl/common/common.h>
Calculate the area of a polygon given a point cloud that defines the polygon.
polygon | point cloud that contains those vertices that comprises the polygon. Vertices are stored in counterclockwise. |
Definition at line 414 of file common.hpp.
References pcl::PointCloud< PointT >::size().
| 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.
[in] | cloud | the input point cloud |
[in] | indices | the point cloud indices that need to be used |
[out] | centroid | the output centroid |
Definition at line 129 of file centroid.hpp.
References pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().
| 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.
[in] | cloud | the input point cloud |
[in] | indices | the point cloud indices that need to be used |
[out] | centroid | the output centroid |
Definition at line 171 of file centroid.hpp.
References pcl::compute3DCentroid(), and pcl::PointIndices::indices.
| 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.
[in] | cloud | the input point cloud |
[out] | centroid | the output centroid |
Definition at line 85 of file centroid.hpp.
References pcl::PointCloud< PointT >::empty(), pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().
| 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.
[in] | cloud_iterator | an iterator over the input point cloud |
[out] | centroid | the output centroid |
Definition at line 56 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::TransformationEstimationSVD< PointT, PointT, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimation3Point< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, pcl::Normal, float >::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 >::selectBase(), and pcl::gpu::people::label_skeleton::sortIndicesToBlob2().
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.
[in] | cloud | |
[in] | indices | point cloud indices that need to be used |
[out] | centroid | This is an overloaded function provided for convenience. See the documentation for computeCentroid(). |
Definition at line 913 of file centroid.hpp.
References pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().
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.
[in] | cloud | input point cloud |
[out] | centroid | output centroid |
0
, then the centroid is not changed, thus is not valid. Definition at line 894 of file centroid.hpp.
References pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().
| inline |
#include <pcl/common/eigen.h>
determines the corresponding eigenvector to the given eigenvalue of the symmetric positive semi definite input matrix
[in] | mat | symmetric positive semi definite input matrix |
[in] | eigenvalue | the eigenvalue which corresponding eigenvector is to be computed |
[out] | eigenvector | the 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().
| 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.
[in] | cloud | the input point cloud |
[in] | centroid | the centroid of the set of points in the cloud |
[out] | covariance_matrix | the resultant 3x3 covariance matrix |
Definition at line 180 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().
| 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.
[in] | cloud | the input point cloud |
[in] | indices | the point cloud indices that need to be used |
[in] | centroid | the centroid of the set of points in the cloud |
[out] | covariance_matrix | the resultant 3x3 covariance matrix |
Definition at line 263 of file centroid.hpp.
References pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().
| 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.
[in] | cloud | the input point cloud |
[in] | indices | subset of points given by their indices |
[out] | covariance_matrix | the resultant 3x3 covariance matrix |
Definition at line 422 of file centroid.hpp.
References pcl::PointCloud< PointT >::is_dense, and pcl::isFinite().
| 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.
[in] | cloud | the input point cloud |
[in] | indices | the point cloud indices that need to be used |
[in] | centroid | the centroid of the set of points in the cloud |
[out] | covariance_matrix | the resultant 3x3 covariance matrix |
Definition at line 334 of file centroid.hpp.
References pcl::computeCovarianceMatrix(), and pcl::PointIndices::indices.
| 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.
[in] | cloud | the input point cloud |
[in] | indices | subset of points given by their indices |
[out] | covariance_matrix | the resultant 3x3 covariance matrix |
Definition at line 476 of file centroid.hpp.
References pcl::computeCovarianceMatrix(), and pcl::PointIndices::indices.
| 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.
[in] | cloud | the input point cloud |
[out] | covariance_matrix | the resultant 3x3 covariance matrix |
Definition at line 368 of file centroid.hpp.
References pcl::PointCloud< PointT >::is_dense, pcl::isFinite(), and pcl::PointCloud< PointT >::size().
| 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.
[in] | cloud | the input point cloud |
[in] | centroid | the centroid of the set of points in the cloud |
[out] | covariance_matrix | the resultant 3x3 covariance matrix |
Definition at line 251 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().
| 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.
[in] | cloud | the input point cloud |
[in] | indices | the point cloud indices that need to be used |
[in] | centroid | the centroid of the set of points in the cloud |
[out] | covariance_matrix | the resultant 3x3 covariance matrix |
Definition at line 344 of file centroid.hpp.
References pcl::computeCovarianceMatrix().
| 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.
[in] | cloud | the input point cloud |
[in] | indices | the point cloud indices that need to be used |
[in] | centroid | the centroid of the set of points in the cloud |
[out] | covariance_matrix | the resultant 3x3 covariance matrix |
Definition at line 358 of file centroid.hpp.
References pcl::computeCovarianceMatrixNormalized(), and pcl::PointIndices::indices.
| 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.
[in] | cloud | the input point cloud |
[in] | indices | subset of points given by their indices |
[out] | covariance_matrix | the resultant 3x3 covariance matrix |
[out] | centroid | the centroid of the set of points in the cloud |
Definition at line 557 of file centroid.hpp.
References pcl::PointCloud< PointT >::is_dense, pcl::isFinite(), pcl::K, and pcl::PointCloud< PointT >::size().
| 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.
[in] | cloud | the input point cloud |
[in] | indices | subset of points given by their indices |
[out] | centroid | the centroid of the set of points in the cloud |
[out] | covariance_matrix | the resultant 3x3 covariance matrix |
Definition at line 630 of file centroid.hpp.
References pcl::computeMeanAndCovarianceMatrix(), and pcl::PointIndices::indices.
| 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.
[in] | cloud | the input point cloud |
[out] | covariance_matrix | the resultant 3x3 covariance matrix |
[out] | centroid | the centroid of the set of points in the cloud |
Definition at line 485 of file centroid.hpp.
References pcl::isFinite(), and pcl::K.
Referenced by pcl::computeMeanAndCovarianceMatrix(), pcl::computePointNormal(), pcl::NormalEstimation< PointInT, PointNT >::computePointNormal(), pcl::SampleConsensusModelRegistration< PointT >::computeSampleDistanceThreshold(), pcl::getPrincipalTransformation(), pcl::GridProjection< PointNT >::getProjectionWithPlaneFit(), pcl::isPointIn2DPolygon(), pcl::SampleConsensusModelStick< PointT >::optimizeModelCoefficients(), pcl::SampleConsensusModelPlane< PointT >::optimizeModelCoefficients(), pcl::ExtractPolygonalPrismData< PointT >::segment(), and pcl::OrganizedMultiPlaneSegmentation< pcl::PointXYZRGBA, pcl::Normal, pcl::Label >::segment().
| 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:
[in,out] | begin,end | Iterators that mark the beginning and end of the value range. These values will be reordered! |
[in] | f | A 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) |
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().
| inline |
#include <pcl/common/centroid.h>
General, all purpose nD centroid estimation for a set of points using their indices.
cloud | the input point cloud |
indices | the point cloud indices that need to be used |
centroid | the output centroid |
Definition at line 840 of file centroid.hpp.
| inline |
#include <pcl/common/centroid.h>
General, all purpose nD centroid estimation for a set of points using their indices.
cloud | the input point cloud |
indices | the point cloud indices that need to be used |
centroid | the output centroid |
Definition at line 863 of file centroid.hpp.
References pcl::computeNDCentroid(), and pcl::PointIndices::indices.
| inline |
#include <pcl/common/centroid.h>
General, all purpose nD centroid estimation for a set of points using their indices.
cloud | the input point cloud |
centroid | the output centroid |
Definition at line 818 of file centroid.hpp.
References pcl::PointCloud< PointT >::empty().
Referenced by pcl::computeNDCentroid().
| inline |
#include <pcl/common/io.h>
Concatenate two pcl::PCLPointCloud2.
[in] | cloud1 | the first input point cloud dataset |
[in] | cloud2 | the second input point cloud dataset |
[out] | cloud_out | the resultant output point cloud dataset |
Definition at line 266 of file io.h.
References pcl::PCLPointCloud2::concatenate().
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>
[in] | cloud1 | the first input point cloud dataset |
[in] | cloud2 | the second input point cloud dataset |
[out] | cloud_out | the resultant output point cloud dataset |
Definition at line 248 of file io.h.
References pcl::PointCloud< PointT >::concatenate().
Referenced by pcl::PCLPointCloud2::concatenate(), pcl::PolygonMesh::concatenate(), pcl::PointCloud< pcl::RGB >::concatenate(), pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::insertRange(), pcl::PolygonMesh::operator+=(), pcl::PointCloud< pcl::RGB >::operator+=(), pcl::outofcore::OutofcoreOctreeBaseNode::queryBBIncludes(), and pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::read().
| inline |
#include <pcl/common/io.h>
Concatenate two pcl::PolygonMesh.
[in] | mesh1 | the first input mesh |
[in] | mesh2 | the second input mesh |
[out] | mesh_out | the resultant output mesh |
Definition at line 281 of file io.h.
References pcl::PolygonMesh::concatenate().
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.
[in] | cloud1_in | the first input dataset |
[in] | cloud2_in | the second input dataset (overwrites the fields of the first dataset for those that are shared) |
[out] | cloud_out | the output dataset created by concatenating all the fields in the input datasets |
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.
[in] | cloud1_in | the first input dataset |
[in] | cloud2_in | the second input dataset (overwrites the fields of the first dataset for those that are shared) |
[out] | cloud_out | the resultant output dataset created by the concatenation of all the fields in the input datasets |
Definition at line 305 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.
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.
[in] | point_in | the source point |
[out] | point_out | the target point |
Definition at line 137 of file copy_point.hpp.
Referenced by pcl::FilterIndices< PointInT >::applyFilter(), pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::MovingLeastSquares< PointInT, PointOutT >::copyMissingFields(), pcl::copyPointCloud(), pcl::detail::copyPointCloudMemcpy(), pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::determineCorrespondences(), pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::determineCorrespondences(), pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::determineCorrespondences(), pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >::determineReciprocalCorrespondences(), pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::determineReciprocalCorrespondences(), pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::determineReciprocalCorrespondences(), pcl::gpu::extractEuclideanClusters(), pcl::search::Search< PointXYZRGB >::nearestKSearchT(), pcl::KdTree< FeatureT >::nearestKSearchT(), pcl::KdTree< FeatureT >::radiusSearchT(), and pcl::search::Search< PointXYZRGB >::radiusSearchT().
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.
[in] | cloud_in | the input point cloud dataset |
[in] | indices | the vector of indices representing the points to be copied from cloud_in |
[out] | cloud_out | the resultant output point cloud dataset |
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.
[in] | cloud_in | the input point cloud dataset |
[in] | indices | the vector of indices representing the points to be copied from cloud_in |
[out] | cloud_out | the resultant output point cloud dataset |
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.
[in] | cloud_in | the input point cloud dataset |
[out] | cloud_out | the resultant output point cloud dataset |
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.
[in] | cloud_in | the input point cloud dataset |
[in] | indices | the vector of indices representing the points to be copied from cloud_in |
[out] | cloud_out | the resultant output point cloud dataset |
Definition at line 190 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.
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.
[in] | cloud_in | the input point cloud dataset |
[in] | indices | the PointIndices structure representing the points to be copied from cloud_in |
[out] | cloud_out | the resultant output point cloud dataset |
Definition at line 219 of file io.hpp.
References pcl::copyPointCloud(), and pcl::PointIndices::indices.
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.
[in] | cloud_in | the input point cloud dataset |
[in] | indices | the vector of indices representing the points to be copied from cloud_in |
[out] | cloud_out | the resultant output point cloud dataset |
Definition at line 267 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.
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.
[in] | cloud_in | the input point cloud dataset |
[out] | cloud_out | the resultant output point cloud dataset |
Definition at line 144 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::addPointCloud(), pcl::outofcore::OutofcoreOctreeBaseNode::addPointCloud_and_genLOD(), pcl::LineRGBD< PointXYZT, PointRGBT >::addTemplate(), pcl::keypoints::internal::AgastApplyNonMaxSuppresion< Out >::AgastApplyNonMaxSuppresion(), pcl::keypoints::internal::AgastDetector< Out >::AgastDetector(), pcl::FastBilateralFilterOMP< PointT >::applyFilter(), pcl::MedianFilter< PointT >::applyFilter(), pcl::FastBilateralFilter< PointT >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilter(), pcl::FilterIndices< PointInT >::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::occlusion_reasoning::ZBuffering< ModelT, SceneT >::filter(), pcl::occlusion_reasoning::filter(), pcl::Filter< pcl::PointXYZRGBL >::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::queryBBIncludes(), and pcl::io::savePLYFile().
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.
[in] | cloud_in | the input point cloud dataset |
[in] | indices | the vector of indices representing the points to be copied from cloud_in |
[out] | cloud_out | the resultant output point cloud dataset |
Definition at line 162 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.
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.
[in] | cloud_in | the input point cloud dataset |
[in] | indices | the PointIndices structure representing the points to be copied from cloud_in |
[out] | cloud_out | the resultant output point cloud dataset |
Definition at line 210 of file io.hpp.
References pcl::copyPointCloud(), and pcl::PointIndices::indices.
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.
[in] | cloud_in | the input point cloud dataset |
[in] | indices | the vector of indices representing the points to be copied from cloud_in |
[out] | cloud_out | the resultant output point cloud dataset |
Definition at line 228 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.
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.
[in] | cloud_in | the input point cloud dataset |
[out] | cloud_out | the resultant output point cloud dataset |
top | ||
bottom | ||
left | ||
right | Position of cloud_in inside cloud_out is given by top, left, bottom right. | |
[in] | border_type | the 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 |
pcl::BadArgumentException | if any of top, bottom, left or right is negative. |
Definition at line 339 of file io.hpp.
References pcl::BORDER_CONSTANT, pcl::BORDER_TRANSPARENT, 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.
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the CS norm of the vector between two points.
A | the first point |
B | the second point |
dim | the number of dimensions in A and B (dimensions must match) |
Definition at line 169 of file norms.hpp.
Referenced by pcl::selectNorm().
| inline |
#include <pcl/common/angles.h>
Convert an angle from degrees to radians.
alpha | the input angle (in degrees) |
Definition at line 79 of file angles.hpp.
| inline |
#include <pcl/common/angles.h>
Convert an angle from degrees to radians.
alpha | the input angle (in degrees) |
Definition at line 67 of file angles.hpp.
Referenced by pcl::RangeImage::createFromPointCloud(), pcl::RangeImage::createFromPointCloudWithKnownSize(), pcl::RangeImage::getImpactAngleBasedOnLocalNormal(), pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::initCompute(), and pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::initCompute().
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.
[in] | cloud_in | the input point cloud |
[in] | centroid | the centroid of the point cloud |
[out] | cloud_out | the resultant output XYZ0 dimensions of cloud_in as an Eigen matrix (4 rows, N pts columns) |
Definition at line 761 of file centroid.hpp.
References pcl::PointCloud< PointT >::size().
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.
[in] | cloud_in | the input point cloud |
[in] | centroid | the centroid of the point cloud |
[out] | cloud_out | the resultant output point cloud |
Definition at line 673 of file centroid.hpp.
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.
[in] | cloud_in | the input point cloud |
[in] | indices | the set of point indices to use from the input point cloud |
[in] | centroid | the centroid of the point cloud |
[out] | cloud_out | the resultant output XYZ0 dimensions of cloud_in as an Eigen matrix (4 rows, N pts columns) |
Definition at line 784 of file centroid.hpp.
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.
[in] | cloud_in | the input point cloud |
[in] | indices | the set of point indices to use from the input point cloud |
[out] | centroid | the centroid of the point cloud |
cloud_out | the resultant output point cloud |
Definition at line 690 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.
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.
[in] | cloud_in | the input point cloud |
[in] | indices | the set of point indices to use from the input point cloud |
[in] | centroid | the centroid of the point cloud |
[out] | cloud_out | the resultant output XYZ0 dimensions of cloud_in as an Eigen matrix (4 rows, N pts columns) |
Definition at line 808 of file centroid.hpp.
References pcl::demeanPointCloud(), and pcl::PointIndices::indices.
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.
[in] | cloud_in | the input point cloud |
[in] | indices | the set of point indices to use from the input point cloud |
[out] | centroid | the centroid of the point cloud |
cloud_out | the resultant output point cloud |
Definition at line 720 of file centroid.hpp.
References pcl::demeanPointCloud(), and pcl::PointIndices::indices.
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.
[in] | cloud_iterator | an iterator over the input point cloud |
[in] | centroid | the centroid of the point cloud |
[out] | cloud_out | the resultant output XYZ0 dimensions of cloud_in as an Eigen matrix (4 rows, N pts columns) |
[in] | npts | the 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 730 of file centroid.hpp.
References pcl::ConstCloudIterator< PointT >::isValid(), and pcl::ConstCloudIterator< PointT >::reset().
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.
[in] | cloud_iterator | an iterator over the input point cloud |
[in] | centroid | the centroid of the point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | npts | the 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 640 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::TransformationEstimationSVD< PointT, PointT, 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().
| inline |
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the div norm of the vector between two points.
A | the first point |
B | the second point |
dim | the number of dimensions in A and B (dimensions must match) |
Definition at line 183 of file norms.hpp.
Referenced by pcl::selectNorm().
| inline |
#include <pcl/common/eigen.h>
determine the smallest eigenvalue and its corresponding eigenvector
[in] | mat | input matrix that needs to be symmetric and positive semi definite |
[out] | eigenvectors | the corresponding eigenvector to the smallest eigenvalue of the input matrix |
[out] | eigenvalues | the smallest eigenvalue of the input matrix |
| inline |
#include <pcl/common/eigen.h>
determine the smallest eigenvalue and its corresponding eigenvector
[in] | mat | input matrix that needs to be symmetric and positive semi definite |
[out] | eigenvalue | the smallest eigenvalue of the input matrix |
[out] | eigenvector | the corresponding eigenvector to the smallest eigenvalue of the input matrix |
Definition at line 133 of file eigen.hpp.
Referenced by pcl::approximatePolygon2D().
| inline |
#include <pcl/common/eigen.h>
determines the eigenvalues and corresponding eigenvectors of the symmetric positive semi definite input matrix
[in] | mat | symmetric positive semi definite input matrix |
[out] | evecs | corresponding eigenvectors in correct order according to eigenvalues |
[out] | evals | resulting eigenvalues in ascending order |
Definition at line 334 of file eigen.hpp.
References pcl::computeRoots(), and pcl::geometry::distance().
| inline |
#include <pcl/common/eigen.h>
determines the eigenvector and eigenvalue of the smallest eigenvalue of the symmetric positive semi definite input matrix
[in] | mat | symmetric positive semi definite input matrix |
[out] | eigenvalue | smallest eigenvalue of the input matrix |
[out] | eigenvector | the corresponding eigenvector for the input eigenvalue |
Definition at line 296 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< pcl::PointXYZRGBA, pcl::Normal >::computePointNormal(), pcl::IntegralImageNormalEstimation< pcl::PointXYZRGBA, pcl::Normal >::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::SampleConsensusModelStick< PointT >::optimizeModelCoefficients(), pcl::SampleConsensusModelPlane< PointT >::optimizeModelCoefficients(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseTomasi(), pcl::ExtractPolygonalPrismData< PointT >::segment(), pcl::OrganizedMultiPlaneSegmentation< pcl::PointXYZRGBA, pcl::Normal, pcl::Label >::segment(), pcl::solvePlaneParameters(), and pcl::gpu::people::label_skeleton::sortIndicesToBlob2().
| inline |
#include <pcl/common/eigen.h>
determines the eigenvalues of the symmetric positive semi definite input matrix
[in] | mat | symmetric positive semi definite input matrix |
[out] | evals | resulting eigenvalues in ascending order |
Definition at line 320 of file eigen.hpp.
References pcl::computeRoots().
| inline |
#include <pcl/common/common.h>
Compute the smallest angle between two 3D vectors in radians (default) or degree.
v1 | the first 3D vector (represented as a Eigen::Vector3f) |
v2 | the second 3D vector (represented as a Eigen::Vector3f) |
in_degree | determine if angle should be in radians or degrees |
Definition at line 59 of file common.hpp.
References M_PI.
| inline |
#include <pcl/common/common.h>
Compute the smallest angle between two 3D vectors in radians (default) or degree.
v1 | the first 3D vector (represented as a Eigen::Vector4f) |
v2 | the second 3D vector (represented as a Eigen::Vector4f) |
in_degree | determine if angle should be in radians or degrees |
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::SampleConsensusModelNormalSphere< PointT, PointNT >::countWithinDistance(), pcl::SampleConsensusModelCylinder< pcl::PointXYZRGB, PointNT >::countWithinDistance(), pcl::SampleConsensusModelCone< pcl::PointXYZRGB, PointNT >::countWithinDistance(), pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::countWithinDistanceStandard(), pcl::SampleConsensusModelNormalSphere< PointT, PointNT >::getDistancesToModel(), pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::getDistancesToModel(), pcl::SampleConsensusModelCylinder< pcl::PointXYZRGB, PointNT >::getDistancesToModel(), pcl::SampleConsensusModelCone< pcl::PointXYZRGB, PointNT >::getDistancesToModel(), pcl::SampleConsensusModelParallelLine< PointT >::isModelValid(), pcl::SampleConsensusModelPerpendicularPlane< PointT >::isModelValid(), pcl::SampleConsensusModelCylinder< pcl::PointXYZRGB, PointNT >::isModelValid(), pcl::SampleConsensusModelCone< pcl::PointXYZRGB, PointNT >::isModelValid(), pcl::SampleConsensusModelNormalSphere< PointT, PointNT >::selectWithinDistance(), pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::selectWithinDistance(), pcl::SampleConsensusModelCylinder< pcl::PointXYZRGB, PointNT >::selectWithinDistance(), and pcl::SampleConsensusModelCone< pcl::PointXYZRGB, PointNT >::selectWithinDistance().
| inline |
#include <pcl/common/common.h>
Compute the radius of a circumscribed circle for a triangle formed of three points pa, pb, and pc.
pa | the first point |
pb | the second point |
pc | the third point |
Definition at line 383 of file common.hpp.
Referenced by pcl::ConcaveHull< PointInT >::performReconstruction().
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.
[in] | in | the Eigen MatrixXf format containing XYZ0 / point |
[out] | out | the resultant point cloud message |
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.
[in] | t | the input transformation matrix |
[in] | roll | the resulting roll angle |
[in] | pitch | the resulting pitch angle |
[in] | yaw | the resulting yaw angle |
Definition at line 585 of file eigen.hpp.
Referenced by pcl::tracking::ParticleXYZRPY::sample().
| inline |
#include <pcl/common/io.h>
Get the index of a specified field (i.e., dimension/channel)
[in] | cloud | the point cloud message |
[in] | field_name | the string defining the field name |
Definition at line 60 of file io.h.
References pcl::geometry::distance(), and pcl::PCLPointCloud2::fields.
| inline |
#include <pcl/common/impl/io.hpp>
Get the index of a specified field (i.e., dimension/channel)
PointT | datatype for which fields is being queries |
[in] | field_name | the string defining the field name |
[in] | fields | a vector to the original PCLPointField vector that the raw PointCloud message contains |
Definition at line 73 of file io.hpp.
References pcl::geometry::distance().
| inline |
#include <pcl/common/impl/io.hpp>
Get the index of a specified field (i.e., dimension/channel)
PointT | datatype for which fields is being queries |
[in] | field_name | the string defining the field name |
[out] | fields | a vector to the original PCLPointField vector that the raw PointCloud message contains |
| inline |
| inline |
#include <pcl/common/io.h>
Obtains the size of a specific field data type in bytes.
[in] | datatype | the field data type (see PCLPointField.h) |
Definition at line 119 of file io.h.
References pcl::PCLPointField::FLOAT32, pcl::PCLPointField::FLOAT64, pcl::PCLPointField::INT16, pcl::PCLPointField::INT32, pcl::PCLPointField::INT8, pcl::PCLPointField::UINT16, pcl::PCLPointField::UINT32, and pcl::PCLPointField::UINT8.
Referenced by pcl::PCDWriter::generateHeader(), pcl::visualization::PointCloudColorHandlerGenericField< PointT >::getColor(), pcl::PCDWriter::writeBinary(), and pcl::PCDWriter::writeBinaryCompressed().
| inline |
#include <pcl/common/io.h>
Get the available point cloud fields as a space separated string.
[in] | cloud | a pointer to the PointCloud message |
Definition at line 108 of file io.h.
References pcl::PCLPointCloud2::fields.
| inline |
| inline |
#include <pcl/common/io.h>
Obtains the type of the PCLPointField from a specific size and type.
[in] | size | the size in bytes of the data field |
[in] | type | a char describing the type of the field ('F' = float, 'I' = signed, 'U' = unsigned) |
Definition at line 158 of file io.h.
References pcl::PCLPointField::FLOAT32, pcl::PCLPointField::FLOAT64, pcl::PCLPointField::INT16, pcl::PCLPointField::INT32, pcl::PCLPointField::INT8, pcl::PCLPointField::UINT16, pcl::PCLPointField::UINT32, and pcl::PCLPointField::UINT8.
Referenced by pcl::PCDWriter::generateHeader().
| inline |
#include <pcl/common/io.h>
Obtains the type of the PCLPointField from a specific PCLPointField as a char.
[in] | type | the PCLPointField field type |
Definition at line 199 of file io.h.
References pcl::PCLPointField::FLOAT32, pcl::PCLPointField::FLOAT64, pcl::PCLPointField::INT16, pcl::PCLPointField::INT32, pcl::PCLPointField::INT8, pcl::PCLPointField::UINT16, pcl::PCLPointField::UINT32, and pcl::PCLPointField::UINT8.
| inline |
#include <pcl/common/common.h>
Get the point at maximum distance from a given point and a given pointcloud.
cloud | the point cloud data message |
pivot_pt | the point from where to compute the distance |
max_pt | the 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, GASDSignature984 >::computeFeature(), pcl::VFHEstimation< PointInT, PointNT, PointOutT >::computePointSPFHSignature(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::computeRFAndShapeDistribution(), and pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::sgurf().
| inline |
#include <pcl/common/common.h>
Get the point at maximum distance from a given point and a given pointcloud.
cloud | the point cloud data message |
indices | the vector of point indices to use from cloud |
pivot_pt | the point from where to compute the distance |
max_pt | the 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.
| inline |
#include <pcl/common/distances.h>
Obtain the maximum segment in a given set of points, and return the minimum and maximum points.
[in] | cloud | the point cloud dataset |
[in] | indices | a set of point indices to use from cloud |
[out] | pmin | the coordinates of the "minimum" point in cloud (one end of the segment) |
[out] | pmax | the coordinates of the "maximum" point in cloud (the other end of the segment) |
Definition at line 146 of file distances.h.
| inline |
#include <pcl/common/distances.h>
Obtain the maximum segment in a given set of points, and return the minimum and maximum points.
[in] | cloud | the point cloud dataset |
[out] | pmin | the coordinates of the "minimum" point in cloud (one end of the segment) |
[out] | pmax | the coordinates of the "maximum" point in cloud (the other end of the segment) |
Definition at line 106 of file distances.h.
References pcl::PointCloud< PointT >::size().
| inline |
#include <pcl/common/common.h>
Compute both the mean and the standard deviation of an array of values.
values | the array of values |
mean | the resultant mean of the distribution |
stddev | the resultant standard deviation of the distribution |
Definition at line 124 of file common.hpp.
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.
values | the array of values |
mean | the resultant mean of the distribution |
stddev | the resultant standard deviation of the distribution |
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.
cloud | the cloud containing multi-dimensional histograms |
idx | point index representing the histogram that we need to compute min/max for |
field_name | the field name containing the multi-dimensional histogram |
min_p | the resultant minimum |
max_p | the resultant maximum |
| inline |
#include <pcl/common/common.h>
Get the minimum and maximum values on a point histogram.
histogram | the point representing a multi-dimensional histogram |
len | the length of the histogram |
min_p | the resultant minimum |
max_p | the resultant maximum |
Definition at line 400 of file common.hpp.
Referenced by pcl::MaximumLikelihoodSampleConsensus< PointT >::computeModel().
| 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.
[in] | cloud | the point cloud data message |
[in] | indices | the vector of point indices to use from cloud |
[out] | min_pt | the resultant minimum bounds |
[out] | max_pt | the resultant maximum bounds |
Definition at line 348 of file common.hpp.
References pcl::PointCloud< PointT >::is_dense.
| 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.
[in] | cloud | the point cloud data message |
[in] | indices | the vector of point indices to use from cloud |
[out] | min_pt | the resultant minimum bounds |
[out] | max_pt | the resultant maximum bounds |
Definition at line 340 of file common.hpp.
References pcl::getMinMax3D(), and pcl::PointIndices::indices.
| 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.
[in] | cloud | the point cloud data message |
[out] | min_pt | the resultant minimum bounds |
[out] | max_pt | the resultant maximum bounds |
Definition at line 305 of file common.hpp.
References pcl::PointCloud< PointT >::is_dense, and pcl::PointCloud< PointT >::points.
| 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.
[in] | cloud | the point cloud data message |
[out] | min_pt | the resultant minimum bounds |
[out] | max_pt | the resultant maximum bounds |
Definition at line 295 of file common.hpp.
Referenced by pcl::gpu::people::buildTree(), pcl::tracking::ParticleFilterTracker< PointInT, StateT >::calcBoundingBox(), pcl::GASDEstimation< PointInT, GASDSignature984 >::computeFeature(), pcl::gpu::DataSource::DataSource(), pcl::octree::OctreePointCloud< PointT, OctreeContainerPointIndex, OctreeContainerEmpty, OctreeBase< OctreeContainerPointIndex, OctreeContainerEmpty > >::defineBoundingBox(), pcl::GridProjection< PointNT >::getBoundingBox(), pcl::MarchingCubes< PointNT >::getBoundingBox(), pcl::getMinMax3D(), pcl::kinfuLS::WorldModel< pcl::PointXYZI >::getWorldAsCubes(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, pcl::Normal, float >::initCompute(), pcl::MovingLeastSquares< PointInT, PointOutT >::MLSVoxelGrid::MLSVoxelGrid(), and pcl::gpu::people::label_skeleton::sortIndicesToBlob2().
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.
[in] | in | the point cloud message |
[out] | out | the resultant Eigen MatrixXf format containing XYZ0 / point |
| inline |
#include <pcl/common/common.h>
Get a set of points residing in a box given its bounds.
cloud | the point cloud data message |
min_pt | the minimum bounds |
max_pt | the maximum bounds |
indices | the 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::queryBBIncludes().
| inline |
#include <pcl/common/eigen.h>
Create a transformation from the given translation and Euler angles (intrinsic rotations, ZYX-convention)
[in] | x | the input x translation |
[in] | y | the input y translation |
[in] | z | the input z translation |
[in] | roll | the input roll angle |
[in] | pitch | the input pitch angle |
[in] | yaw | the input yaw angle |
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)
[in] | x | the input x translation |
[in] | y | the input y translation |
[in] | z | the input z translation |
[in] | roll | the input roll angle |
[in] | pitch | the input pitch angle |
[in] | yaw | the input yaw angle |
[out] | t | the resulting transformation matrix |
Definition at line 608 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().
| 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)
[in] | y_direction | the y direction |
[in] | z_axis | the z-axis |
Definition at line 563 of file eigen.hpp.
References pcl::getTransformationFromTwoUnitVectors().
| 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)
[in] | y_direction | the y direction |
[in] | z_axis | the z-axis |
[out] | transformation | the resultant 3D rotation |
Definition at line 554 of file eigen.hpp.
References pcl::getTransFromUnitVectorsZY().
Referenced by pcl::RangeImage::getRotationToViewerCoordinateFrame(), pcl::getTransformationFromTwoUnitVectors(), and pcl::getTransformationFromTwoUnitVectorsAndOrigin().
| 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)
[in] | y_direction | the y direction |
[in] | z_axis | the z-axis |
[in] | origin | the origin |
[in] | transformation | the resultant transformation matrix |
Definition at line 573 of file eigen.hpp.
References pcl::getTransformationFromTwoUnitVectors().
Referenced by pcl::RangeImage::getTransformationToViewerCoordinateFrame().
| 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)
[in] | x_axis | the x-axis |
[in] | y_direction | the y direction |
Definition at line 544 of file eigen.hpp.
References pcl::getTransFromUnitVectorsXY().
| 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)
[in] | x_axis | the x-axis |
[in] | y_direction | the y direction |
[out] | transformation | the resultant 3D rotation |
Definition at line 528 of file eigen.hpp.
Referenced by pcl::getTransFromUnitVectorsXY().
| 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)
[in] | z_axis | the z-axis |
[in] | y_direction | the y direction |
Definition at line 518 of file eigen.hpp.
References pcl::getTransFromUnitVectorsZY().
| 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)
[in] | z_axis | the z-axis |
[in] | y_direction | the y direction |
[out] | transformation | the resultant 3D rotation |
Definition at line 502 of file eigen.hpp.
Referenced by pcl::getTransformationFromTwoUnitVectors(), and pcl::getTransFromUnitVectorsZY().
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.
[in] | t | the input transformation matrix |
[out] | x | the resulting x translation |
[out] | y | the resulting y translation |
[out] | z | the resulting z translation |
[out] | roll | the resulting roll angle |
[out] | pitch | the resulting pitch angle |
[out] | yaw | the resulting yaw angle |
Definition at line 594 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().
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the HIK norm of the vector between two points.
A | the first point |
B | the second point |
dim | the number of dimensions in A and B (dimensions must match) |
Definition at line 233 of file norms.hpp.
Referenced by pcl::selectNorm().
| inline |
#include <pcl/common/eigen.h>
Calculate the inverse of a 2x2 matrix.
[in] | matrix | matrix to be inverted |
[out] | inverse | the resultant inverted matrix |
| inline |
| inline |
#include <pcl/common/eigen.h>
Calculate the inverse of a 3x3 symmetric matrix.
[in] | matrix | matrix to be inverted |
[out] | inverse | the resultant inverted matrix |
Definition at line 424 of file eigen.hpp.
Referenced by pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::refineCorners().
| 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.
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the JM norm of the vector between two points.
A | the first point |
B | the second point |
dim | the number of dimensions in A and B (dimensions must match) |
Definition at line 128 of file norms.hpp.
Referenced by pcl::selectNorm().
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the K norm of the vector between two points.
A | the first point |
B | the second point |
dim | the number of dimensions in A and B (dimensions must match) |
P1 | the first parameter |
P2 | the second parameter |
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the KL between two discrete probability density functions.
A | the first discrete PDF |
B | the second discrete PDF |
dim | the number of dimensions in A and B (dimensions must match) |
Definition at line 219 of file norms.hpp.
Referenced by pcl::selectNorm().
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the L1 norm of the vector between two points.
A | the first point |
B | the second point |
dim | the number of dimensions in A and B (dimensions must match) |
Definition at line 88 of file norms.hpp.
Referenced by pcl::Narf::getDescriptorDistance(), and pcl::selectNorm().
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the L2 norm of the vector between two points.
A | the first point |
B | the second point |
dim | the number of dimensions in A and B (dimensions must match) |
Definition at line 111 of file norms.hpp.
References pcl::L2_Norm_SQR().
Referenced by pcl::selectNorm().
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the squared L2 norm of the vector between two points.
A | the first point |
B | the second point |
dim | the number of dimensions in A and B (dimensions must match) |
Definition at line 98 of file norms.hpp.
Referenced by pcl::L2_Norm(), and pcl::selectNorm().
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.
line_a | the coefficients of the first line (point, direction) |
line_b | the coefficients of the second line (point, direction) |
pt1_seg | the first point on the line segment |
pt2_seg | the second point on the line segment |
Referenced by pcl::lineWithLineIntersection().
| inline |
#include <pcl/common/impl/intersections.hpp>
Get the intersection of a two 3D lines in space as a 3D point.
[in] | line_a | the coefficients of the first line (point, direction) |
[in] | line_b | the coefficients of the second line (point, direction) |
[out] | point | holder for the computed 3D point |
[in] | sqr_eps | maximum allowable squared distance to the true solution |
Definition at line 49 of file intersections.hpp.
References pcl::lineToLineSegment().
Referenced by pcl::lineWithLineIntersection().
| inline |
#include <pcl/common/impl/intersections.hpp>
Get the intersection of a two 3D lines in space as a 3D point.
[in] | line_a | the coefficients of the first line (point, direction) |
[in] | line_b | the coefficients of the second line (point, direction) |
[out] | point | holder for the computed 3D point |
[in] | sqr_eps | maximum allowable squared distance to the true solution |
Definition at line 69 of file intersections.hpp.
References pcl::lineWithLineIntersection(), and pcl::ModelCoefficients::values.
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the L-infinity norm of the vector between two points.
A | the first point |
B | the second point |
dim | the number of dimensions in A and B (dimensions must match) |
Definition at line 118 of file norms.hpp.
Referenced by pcl::selectNorm().
void pcl::loadBinary | ( | Eigen::MatrixBase< Derived > const & | matrix, |
std::istream & | file | ||
) |
| inline |
#include <pcl/common/angles.h>
Normalize an angle to (-PI, PI].
alpha | the input angle (in radians) |
Definition at line 48 of file angles.hpp.
References M_PI.
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the PF norm of the vector between two points.
A | the first point |
B | the second point |
dim | the number of dimensions in A and B (dimensions must match) |
P1 | the first parameter |
P2 | the second parameter |
| inline |
#include <pcl/common/angles.h>
Convert an angle from radians to degrees.
alpha | the input angle (in radians) |
Definition at line 73 of file angles.hpp.
| inline |
#include <pcl/common/angles.h>
Convert an angle from radians to degrees.
alpha | the input angle (in radians) |
Definition at line 61 of file angles.hpp.
Referenced by pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::computePoint(), and pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::computePointDescriptor().
void pcl::saveBinary | ( | const Eigen::MatrixBase< Derived > & | matrix, |
std::ostream & | file | ||
) |
| inline |
#include <pcl/common/impl/norms.hpp>
Method that calculates any norm type available, based on the norm_type variable.
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().
| inline |
#include <pcl/common/distances.h>
Get the square distance from a point to a line (represented by a point and a direction)
pt | a point |
line_pt | a point on the line (make sure that line_pt[3] = 0 as there are no internal checks!) |
line_dir | the line direction |
Definition at line 75 of file distances.h.
Referenced by pcl::SampleConsensusModelCylinder< pcl::PointXYZRGB, PointNT >::computeModelCoefficients(), pcl::SampleConsensusModelCone< pcl::PointXYZRGB, PointNT >::pointToAxisDistance(), and pcl::SampleConsensusModelCylinder< pcl::PointXYZRGB, PointNT >::pointToLineDistance().
| inline |
#include <pcl/common/distances.h>
Get the square distance from a point to a line (represented by a point and a direction)
pt | a point |
line_pt | a point on the line (make sure that line_pt[3] = 0 as there are no internal checks!) |
line_dir | the line direction |
sqr_length | the squared norm of the line direction |
Definition at line 91 of file distances.h.
| inline |
#include <pcl/common/impl/norms.hpp>
Compute the sublinear norm of the vector between two points.
A | the first point |
B | the second point |
dim | the number of dimensions in A and B (dimensions must match) |
Definition at line 157 of file norms.hpp.
Referenced by pcl::selectNorm().
void pcl::io::swapByte | ( | char * | bytes | ) |
#include <pcl/common/io.h>
swap bytes order of a char array of length N
bytes | char array to swap |
| inline |
#include <pcl/common/impl/transforms.hpp>
Transform a point with members x,y,z.
[in] | point | the point to transform |
[out] | transform | the transformation to apply |
Definition at line 474 of file transforms.hpp.
References pcl::detail::Transformer< Scalar >::se3().
| inline |
#include <pcl/common/impl/transforms.hpp>
Apply an affine transform on a pointcloud having points of type PointXY.
[in] | cloud_in | the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | an affine transformation |
[in] | copy_all_fields | flag 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.
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.
[in] | cloud_in | the input point cloud |
[in] | indices | the set of point indices to use from the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | a rigid transformation |
[in] | copy_all_fields | flag 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.
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.
[in] | cloud_in | the input point cloud |
[in] | indices | the set of point indices to use from the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | an affine transformation (typically a rigid transformation) |
[in] | copy_all_fields | flag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud |
Definition at line 87 of file transforms.h.
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.
[in] | cloud_in | the input point cloud |
[in] | indices | the set of point indices to use from the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | a rigid transformation |
[in] | copy_all_fields | flag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud |
Definition at line 281 of file transforms.h.
References pcl::PointIndices::indices.
void pcl::transformPointCloud | ( | const pcl::PointCloud< PointT > & | cloud_in, |
const pcl::PointIndices & | indices, | ||
pcl::PointCloud< PointT > & | cloud_out, | ||
const Eigen::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.
[in] | cloud_in | the input point cloud |
[in] | indices | the set of point indices to use from the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | an affine transformation (typically a rigid transformation) |
[in] | copy_all_fields | flag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud |
Definition at line 116 of file transforms.h.
References pcl::PointIndices::indices.
| inline |
#include <pcl/common/impl/transforms.hpp>
Apply a rigid transform defined by a 3D offset and a quaternion.
[in] | cloud_in | the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | offset | the translation component of the rigid transformation |
[in] | rotation | the rotation component of the rigid transformation |
[in] | copy_all_fields | flag 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().
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.
[in] | cloud_in | the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | a rigid transformation |
[in] | copy_all_fields | flag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud |
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, GASDSignature984 >::computeFeature(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::computeRFAndShapeDistribution(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeStepLengthMT(), pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::computeTransformation(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation(), pcl::SampleConsensusPrerejective< PointSource, PointTarget, FeatureT >::computeTransformation(), pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::computeTransformation(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, pcl::Normal, float >::computeTransformation(), pcl::GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >::computeTransformation(), pcl::registration::LUM< PointT >::getConcatenatedCloud(), pcl::kinfuLS::WorldModel< pcl::PointXYZI >::getExistingData(), pcl::SampleConsensusPrerejective< PointSource, PointTarget, FeatureT >::getFitness(), pcl::Registration< PointSource, PointTarget >::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, pcl::Normal, float >::validateMatch(), pcl::registration::KFPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateTransformation(), and pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, pcl::Normal, float >::validateTransformation().
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.
[in] | cloud_in | the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | an affine transformation (typically a rigid transformation) |
[in] | copy_all_fields | flag that controls whether the contents of the fields (other than x, y, z) should be copied into the new transformed cloud |
Definition at line 60 of file transforms.h.
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.
[in] | cloud_in | the input point cloud |
[in] | indices | the set of point indices to use from the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | an affine transformation (typically a rigid transformation) |
[in] | copy_all_fields | flag that controls whether the contents of the fields (other than x, y, z, normal_x, normal_y, normal_z) should be copied into the new transformed cloud |
Definition at line 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.
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.
[in] | cloud_in | the input point cloud |
[in] | indices | the set of point indices to use from the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | an affine transformation (typically a rigid transformation) |
[in] | copy_all_fields | flag that controls whether the contents of the fields (other than x, y, z, normal_x, normal_y, normal_z) should be copied into the new transformed cloud |
Definition at line 367 of file transforms.h.
References pcl::PointIndices::indices.
| inline |
#include <pcl/common/impl/transforms.hpp>
Transform a point cloud and rotate its normals using an Eigen transform.
[in] | cloud_in | the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | offset | the translation component of the rigid transformation |
[in] | rotation | the rotation component of the rigid transformation |
[in] | copy_all_fields | flag that controls whether the contents of the fields (other than x, y, z, normal_x, normal_y, normal_z) should be copied into the new transformed cloud |
Definition at line 460 of file transforms.hpp.
References pcl::transformPointCloudWithNormals().
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.
[in] | cloud_in | the input point cloud |
[out] | cloud_out | the resultant output point cloud |
[in] | transform | an affine transformation (typically a rigid transformation) |
[in] | copy_all_fields | flag that controls whether the contents of the fields (other than x, y, z, normal_x, normal_y, normal_z) should be copied into the new transformed cloud |
Definition at line 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().
| inline |
#include <pcl/common/impl/transforms.hpp>
Transform a point with members x,y,z,normal_x,normal_y,normal_z.
[in] | point | the point to transform |
[out] | transform | the transformation to apply |
Definition at line 484 of file transforms.hpp.
References pcl::detail::Transformer< Scalar >::se3(), and pcl::detail::Transformer< Scalar >::so3().
© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/group__common.html