principal_curvatures.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  *
00039  */
00040 
00041 #ifndef PCL_PRINCIPAL_CURVATURES_H_
00042 #define PCL_PRINCIPAL_CURVATURES_H_
00043 
00044 #include <pcl/features/eigen.h>
00045 #include <pcl/features/feature.h>
00046 
00047 namespace pcl
00048 {
00060   template <typename PointInT, typename PointNT, typename PointOutT = pcl::PrincipalCurvatures>
00061   class PrincipalCurvaturesEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00062   {
00063     public:
00064       typedef boost::shared_ptr<PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT> > Ptr;
00065       typedef boost::shared_ptr<const PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00066       using Feature<PointInT, PointOutT>::feature_name_;
00067       using Feature<PointInT, PointOutT>::getClassName;
00068       using Feature<PointInT, PointOutT>::indices_;
00069       using Feature<PointInT, PointOutT>::k_;
00070       using Feature<PointInT, PointOutT>::search_parameter_;
00071       using Feature<PointInT, PointOutT>::surface_;
00072       using Feature<PointInT, PointOutT>::input_;
00073       using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00074 
00075       typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00076       typedef pcl::PointCloud<PointInT> PointCloudIn;
00077 
00079       PrincipalCurvaturesEstimation () : 
00080         projected_normals_ (), 
00081         xyz_centroid_ (Eigen::Vector3f::Zero ()), 
00082         demean_ (Eigen::Vector3f::Zero ()),
00083         covariance_matrix_ (Eigen::Matrix3f::Zero ()),
00084         eigenvector_ (Eigen::Vector3f::Zero ()),
00085         eigenvalues_ (Eigen::Vector3f::Zero ())
00086       {
00087         feature_name_ = "PrincipalCurvaturesEstimation";
00088       };
00089 
00102       void
00103       computePointPrincipalCurvatures (const pcl::PointCloud<PointNT> &normals,
00104                                        int p_idx, const std::vector<int> &indices,
00105                                        float &pcx, float &pcy, float &pcz, float &pc1, float &pc2);
00106 
00107     protected:
00108 
00114       void
00115       computeFeature (PointCloudOut &output);
00116 
00117     private:
00119       std::vector<Eigen::Vector3f> projected_normals_;
00120 
00122       Eigen::Vector3f xyz_centroid_;
00123 
00125       Eigen::Vector3f demean_;
00126 
00128       EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix_;
00129 
00131       Eigen::Vector3f eigenvector_;
00133       Eigen::Vector3f eigenvalues_;
00134   };
00135 }
00136 
00137 #ifdef PCL_NO_PRECOMPILE
00138 #include <pcl/features/impl/principal_curvatures.hpp>
00139 #endif
00140 
00141 #endif  //#ifndef PCL_PRINCIPAL_CURVATURES_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:31:18