Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef PCL_PCA_H
00040 #define PCL_PCA_H
00041
00042 #include <pcl/pcl_base.h>
00043 #include <pcl/pcl_macros.h>
00044
00045 namespace pcl
00046 {
00059 template <typename PointT>
00060 class PCA : public pcl::PCLBase <PointT>
00061 {
00062 public:
00063 typedef pcl::PCLBase <PointT> Base;
00064 typedef typename Base::PointCloud PointCloud;
00065 typedef typename Base::PointCloudPtr PointCloudPtr;
00066 typedef typename Base::PointCloudConstPtr PointCloudConstPtr;
00067 typedef typename Base::PointIndicesPtr PointIndicesPtr;
00068 typedef typename Base::PointIndicesConstPtr PointIndicesConstPtr;
00069
00070 using Base::input_;
00071 using Base::indices_;
00072 using Base::initCompute;
00073 using Base::setInputCloud;
00074
00076 enum FLAG
00077 {
00079 increase,
00081 preserve
00082 };
00083
00087 PCA (bool basis_only = false)
00088 : Base ()
00089 , compute_done_ (false)
00090 , basis_only_ (basis_only)
00091 , eigenvectors_ ()
00092 , coefficients_ ()
00093 , mean_ ()
00094 , eigenvalues_ ()
00095 {}
00096
00101 PCL_DEPRECATED (PCA (const pcl::PointCloud<PointT>& X, bool basis_only = false),
00102 "Use PCA (bool basis_only); setInputCloud (X.makeShared ()); instead");
00103
00107 PCA (PCA const & pca)
00108 : Base (pca)
00109 , compute_done_ (pca.compute_done_)
00110 , basis_only_ (pca.basis_only_)
00111 , eigenvectors_ (pca.eigenvectors_)
00112 , coefficients_ (pca.coefficients_)
00113 , mean_ (pca.mean_)
00114 , eigenvalues_ (pca.eigenvalues_)
00115 {}
00116
00120 inline PCA&
00121 operator= (PCA const & pca)
00122 {
00123 eigenvectors_ = pca.eigenvectors;
00124 coefficients_ = pca.coefficients;
00125 eigenvalues_ = pca.eigenvalues;
00126 mean_ = pca.mean;
00127 return (*this);
00128 }
00129
00133 inline void
00134 setInputCloud (const PointCloudConstPtr &cloud)
00135 {
00136 Base::setInputCloud (cloud);
00137 compute_done_ = false;
00138 }
00139
00143 inline Eigen::Vector4f&
00144 getMean ()
00145 {
00146 if (!compute_done_)
00147 initCompute ();
00148 if (!compute_done_)
00149 PCL_THROW_EXCEPTION (InitFailedException,
00150 "[pcl::PCA::getMean] PCA initCompute failed");
00151 return (mean_);
00152 }
00153
00157 inline Eigen::Matrix3f&
00158 getEigenVectors ()
00159 {
00160 if (!compute_done_)
00161 initCompute ();
00162 if (!compute_done_)
00163 PCL_THROW_EXCEPTION (InitFailedException,
00164 "[pcl::PCA::getEigenVectors] PCA initCompute failed");
00165 return (eigenvectors_);
00166 }
00167
00171 inline Eigen::Vector3f&
00172 getEigenValues ()
00173 {
00174 if (!compute_done_)
00175 initCompute ();
00176 if (!compute_done_)
00177 PCL_THROW_EXCEPTION (InitFailedException,
00178 "[pcl::PCA::getEigenVectors] PCA getEigenValues failed");
00179 return (eigenvalues_);
00180 }
00181
00185 inline Eigen::MatrixXf&
00186 getCoefficients ()
00187 {
00188 if (!compute_done_)
00189 initCompute ();
00190 if (!compute_done_)
00191 PCL_THROW_EXCEPTION (InitFailedException,
00192 "[pcl::PCA::getEigenVectors] PCA getCoefficients failed");
00193 return (coefficients_);
00194 }
00195
00201 inline void
00202 update (const PointT& input, FLAG flag = preserve);
00203
00209 inline void
00210 project (const PointT& input, PointT& projection);
00211
00217 inline void
00218 project (const PointCloud& input, PointCloud& projection);
00219
00225 inline void
00226 reconstruct (const PointT& projection, PointT& input);
00227
00233 inline void
00234 reconstruct (const PointCloud& projection, PointCloud& input);
00235
00236 private:
00237 inline bool
00238 initCompute ();
00239
00240 bool compute_done_;
00241 bool basis_only_;
00242 Eigen::Matrix3f eigenvectors_;
00243 Eigen::MatrixXf coefficients_;
00244 Eigen::Vector4f mean_;
00245 Eigen::Vector3f eigenvalues_;
00246 };
00247 }
00248
00249 #include <pcl/common/impl/pca.hpp>
00250
00251 #endif // PCL_PCA_H
00252