#include <pca.h>
Public Types | |
typedef pcl::PCLBase< PointT > | Base |
enum | FLAG { increase, preserve } |
typedef Base::PointCloud | PointCloud |
typedef Base::PointCloudConstPtr | PointCloudConstPtr |
typedef Base::PointCloudPtr | PointCloudPtr |
typedef Base::PointIndicesConstPtr | PointIndicesConstPtr |
typedef Base::PointIndicesPtr | PointIndicesPtr |
Public Member Functions | |
Eigen::MatrixXf & | getCoefficients () |
Eigen::Vector3f & | getEigenValues () |
Eigen::Matrix3f & | getEigenVectors () |
Eigen::Vector4f & | getMean () |
Mean accessor. | |
PCA & | operator= (PCA const &pca) |
PCA (bool basis_only=false) | |
Default Constructor. | |
PCA (PCA const &pca) | |
PCL_DEPRECATED (PCA(const pcl::PointCloud< PointT > &X, bool basis_only=false),"Use PCA (bool basis_only); setInputCloud (X.makeShared ()); instead") | |
Constructor with direct computation X input m*n matrix (ie n vectors of R(m)) basis_only flag to compute only the PCA basis. | |
void | project (const PointT &input, PointT &projection) |
void | project (const PointCloud &input, PointCloud &projection) |
void | reconstruct (const PointT &projection, PointT &input) |
void | reconstruct (const PointCloud &projection, PointCloud &input) |
void | setInputCloud (const PointCloudConstPtr &cloud) |
Provide a pointer to the input dataset. | |
void | update (const PointT &input, FLAG flag=preserve) |
Private Member Functions | |
bool | initCompute () |
This method should get called before starting the actual computation. | |
Private Attributes | |
bool | basis_only_ |
Eigen::MatrixXf | coefficients_ |
bool | compute_done_ |
Eigen::Vector3f | eigenvalues_ |
Eigen::Matrix3f | eigenvectors_ |
Eigen::Vector4f | mean_ |
Principal Component analysis (PCA) class.
Principal components are extracted by singular values decomposition on the covariance matrix of the centered input cloud. Available data after pca computation are the mean of the input data, the eigenvalues (in descending order) and corresponding eigenvectors.
Other methods allow projection in the eigenspace, reconstruction from eigenspace and update of the eigenspace with a new datum (according Matej Artec, Matjaz Jogan and Ales Leonardis: "Incremental PCA for On-line Visual Learning and Recognition").
typedef pcl::PCLBase<PointT> pcl::PCA< PointT >::Base |
typedef Base::PointCloud pcl::PCA< PointT >::PointCloud |
Reimplemented from pcl::PCLBase< PointT >.
typedef Base::PointCloudConstPtr pcl::PCA< PointT >::PointCloudConstPtr |
Reimplemented from pcl::PCLBase< PointT >.
typedef Base::PointCloudPtr pcl::PCA< PointT >::PointCloudPtr |
Reimplemented from pcl::PCLBase< PointT >.
typedef Base::PointIndicesConstPtr pcl::PCA< PointT >::PointIndicesConstPtr |
Reimplemented from pcl::PCLBase< PointT >.
typedef Base::PointIndicesPtr pcl::PCA< PointT >::PointIndicesPtr |
Reimplemented from pcl::PCLBase< PointT >.
enum pcl::PCA::FLAG |
Eigen::MatrixXf& pcl::PCA< PointT >::getCoefficients | ( | ) | [inline] |
Eigen::Vector3f& pcl::PCA< PointT >::getEigenValues | ( | ) | [inline] |
Eigen::Matrix3f& pcl::PCA< PointT >::getEigenVectors | ( | ) | [inline] |
bool pcl::PCA< PointT >::initCompute | ( | ) | [inline, private] |
This method should get called before starting the actual computation.
Internally, initCompute() does the following:
Reimplemented from pcl::PCLBase< PointT >.
pcl::PCA< PointT >::PCL_DEPRECATED | ( | PCA< PointT >(const pcl::PointCloud< PointT > &X, bool basis_only=false) | , |
"Use PCA< PointT > (bool basis_only); setInputCloud (X.makeShared ()); instead" | |||
) |
Constructor with direct computation X input m*n matrix (ie n vectors of R(m)) basis_only flag to compute only the PCA basis.
void pcl::PCA< PointT >::project | ( | const PointT & | input, |
PointT & | projection | ||
) | [inline] |
Project point on the eigenspace.
[in] | input | point from original dataset |
[out] | projection | the point in eigen vectors space |
InitFailedException |
void pcl::PCA< PointT >::project | ( | const PointCloud & | input, |
PointCloud & | projection | ||
) | [inline] |
Project cloud on the eigenspace.
[in] | input | cloud from original dataset |
[out] | projection | the cloud in eigen vectors space |
InitFailedException |
void pcl::PCA< PointT >::reconstruct | ( | const PointT & | projection, |
PointT & | input | ||
) | [inline] |
Reconstruct point from its projection
[in] | projection | point from eigenvector space |
[out] | input | reconstructed point |
InitFailedException |
void pcl::PCA< PointT >::reconstruct | ( | const PointCloud & | projection, |
PointCloud & | input | ||
) | [inline] |
Reconstruct cloud from its projection
[in] | projection | cloud from eigenvector space |
[out] | input | reconstructed cloud |
InitFailedException |
void pcl::PCA< PointT >::setInputCloud | ( | const PointCloudConstPtr & | cloud | ) | [inline, virtual] |
Provide a pointer to the input dataset.
cloud | the const boost shared pointer to a PointCloud message |
Reimplemented from pcl::PCLBase< PointT >.
void pcl::PCA< PointT >::update | ( | const PointT & | input, |
FLAG | flag = preserve |
||
) | [inline] |
update PCA with a new point
[in] | input | input point |
[in] | flag | update flag |
InitFailedException |
bool pcl::PCA< PointT >::basis_only_ [private] |
Eigen::MatrixXf pcl::PCA< PointT >::coefficients_ [private] |
bool pcl::PCA< PointT >::compute_done_ [private] |
Eigen::Vector3f pcl::PCA< PointT >::eigenvalues_ [private] |
Eigen::Matrix3f pcl::PCA< PointT >::eigenvectors_ [private] |