Classes | Namespaces | Functions
centroid.h File Reference
#include <pcl/point_cloud.h>
#include <pcl/point_traits.h>
#include <pcl/PointIndices.h>
#include <pcl/common/impl/centroid.hpp>
Include dependency graph for centroid.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  pcl::NdCentroidFunctor< PointT >
 Helper functor structure for n-D centroid estimation. More...

Namespaces

namespace  pcl

Functions

template<typename PointT >
unsigned int pcl::compute3DCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::Vector4f &centroid)
 Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector.
template<typename PointT >
unsigned int pcl::compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, Eigen::Vector4f &centroid)
 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 >
unsigned int pcl::compute3DCentroid (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Vector4f &centroid)
 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 >
unsigned int pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4f &centroid, 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 >
unsigned int pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, const Eigen::Vector4f &centroid, 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 >
unsigned int pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Vector4f &centroid, 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 >
unsigned int pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix3f &covariance_matrix)
 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 explicitely 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.
template<typename PointT >
unsigned int pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, Eigen::Matrix3f &covariance_matrix)
 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 explicitely 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.
template<typename PointT >
unsigned int pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix3f &covariance_matrix)
 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 explicitely 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.
template<typename PointT >
unsigned int pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix3d &covariance_matrix)
 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 explicitely 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.
template<typename PointT >
unsigned int pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, Eigen::Matrix3d &covariance_matrix)
 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 explicitely 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.
template<typename PointT >
unsigned int pcl::computeCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix3d &covariance_matrix)
 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 explicitely 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.
template<typename PointT >
unsigned int pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4f &centroid, 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. For small number of points, or if you want explicitely 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.
template<typename PointT >
unsigned int pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, const Eigen::Vector4f &centroid, 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. For small number of points, or if you want explicitely 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.
template<typename PointT >
unsigned int pcl::computeCovarianceMatrixNormalized (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, const Eigen::Vector4f &centroid, 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. For small number of points, or if you want explicitely 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.
template<typename PointT >
unsigned int pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix3f &covariance_matrix, Eigen::Vector4f &centroid)
 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 explicitely 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.
template<typename PointT >
unsigned int pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, Eigen::Matrix3f &covariance_matrix, Eigen::Vector4f &centroid)
 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 explicitely 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.
template<typename PointT >
unsigned int pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix3f &covariance_matrix, Eigen::Vector4f &centroid)
 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 explicitely 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.
template<typename PointT >
unsigned int pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix3d &covariance_matrix, Eigen::Vector4d &centroid)
 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 explicitely 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.
template<typename PointT >
unsigned int pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, Eigen::Matrix3d &covariance_matrix, Eigen::Vector4d &centroid)
 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 explicitely 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.
template<typename PointT >
unsigned int pcl::computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Matrix3d &covariance_matrix, Eigen::Vector4d &centroid)
 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 explicitely 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.
template<typename PointT >
void pcl::computeNDCentroid (const pcl::PointCloud< PointT > &cloud, Eigen::VectorXf &centroid)
 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 &centroid)
 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 pcl::PointIndices &indices, Eigen::VectorXf &centroid)
 General, all purpose nD centroid estimation for a set of points using their indices.
template<typename PointT >
void pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Eigen::Vector4f &centroid, pcl::PointCloud< PointT > &cloud_out)
 Subtract a centroid from a point cloud and return the de-meaned representation.
template<typename PointT >
void pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< int > &indices, const Eigen::Vector4f &centroid, pcl::PointCloud< PointT > &cloud_out)
 Subtract a centroid from a point cloud and return the de-meaned representation.
template<typename PointT >
void pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const Eigen::Vector4f &centroid, Eigen::MatrixXf &cloud_out)
 Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix.
template<typename PointT >
void pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< int > &indices, const Eigen::Vector4f &centroid, Eigen::MatrixXf &cloud_out)
 Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix.
template<typename PointT >
void pcl::demeanPointCloud (const pcl::PointCloud< PointT > &cloud_in, const pcl::PointIndices &indices, const Eigen::Vector4f &centroid, Eigen::MatrixXf &cloud_out)
 Subtract a centroid from a point cloud and return the de-meaned representation as an Eigen matrix.

Detailed Description

Define methods for centroid estimation and covariance matrix calculus

Definition in file centroid.h.



pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:12