#include <boost/function.hpp>#include <boost/bind.hpp>#include <boost/mpl/size.hpp>#include "pcl/pcl_base.h"#include "pcl/common/eigen.h"#include "pcl/kdtree/tree_types.h"#include "pcl/kdtree/kdtree.h"#include "pcl/kdtree/kdtree_flann.h"#include "pcl/kdtree/organized_data.h"#include "pcl/io/io.h"#include "pcl/features/feature.hpp"

Go to the source code of this file.
Classes | |
| class | pcl::Feature< PointInT, PointOutT > |
| Feature represents the base feature class. Some generic 3D operations that are applicable to all features are defined here as static methods. More... | |
| class | pcl::FeatureFromNormals< PointInT, PointNT, PointOutT > |
| struct | pcl::NdCentroidFunctor< PointT > |
| Helper functor structure for n-D centroid estimation. More... | |
Namespaces | |
| namespace | pcl |
Functions | |
| template<typename PointT > | |
| void | pcl::compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Vector4f ¢roid) |
| Compute the 3D (X-Y-Z) centroid of a set of points using their indices and return it as a 3D vector. | |
| template<typename PointT > | |
| void | pcl::compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, Eigen::Vector4f ¢roid) |
| Compute the 3D (X-Y-Z) centroid of a set of points using their indices and return it as a 3D vector. | |
| template<typename PointT > | |
| void | pcl::compute3DCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::Vector4f ¢roid) |
| Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector. | |
| template<typename PointT > | |
| void | pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Vector4f ¢roid, Eigen::Matrix3f &covariance_matrix) |
| 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 computeNormalizedCovarianceMatrix. | |
| template<typename PointT > | |
| void | pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, const Eigen::Vector4f ¢roid, Eigen::Matrix3f &covariance_matrix) |
| 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 computeNormalizedCovarianceMatrix. | |
| template<typename PointT > | |
| void | pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4f ¢roid, Eigen::Matrix3f &covariance_matrix) |
| 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 computeNormalizedCovarianceMatrix. | |
| template<typename PointT > | |
| void | pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Vector4f ¢roid, Eigen::Matrix3f &covariance_matrix) |
| 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. | |
| template<typename PointT > | |
| void | pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, const Eigen::Vector4f ¢roid, Eigen::Matrix3f &covariance_matrix) |
| 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. | |
| template<typename PointT > | |
| void | pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4f ¢roid, Eigen::Matrix3f &covariance_matrix) |
| 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. | |
| template<typename PointT > | |
| void | pcl::computeNDCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::VectorXf ¢roid) |
| General, all purpose nD centroid estimation for a set of points using their indices. | |
| template<typename PointT > | |
| void | pcl::computeNDCentroid (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, Eigen::VectorXf ¢roid) |
| General, all purpose nD centroid estimation for a set of points using their indices. | |
| template<typename PointT > | |
| void | pcl::computeNDCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::VectorXf ¢roid) |
| General, all purpose nD centroid estimation for a set of points using their indices. | |
| void | pcl::solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix, float &nx, float &ny, float &nz, float &curvature) |
| Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squares plane normal and surface curvature. | |
| void | pcl::solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix, const Eigen::Vector4f &point, Eigen::Vector4f &plane_parameters, float &curvature) |
| Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squares plane normal and surface curvature. | |