feature.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_FEATURE_H_
00042 #define PCL_FEATURE_H_
00043 
00044 #if defined __GNUC__
00045 #  pragma GCC system_header 
00046 #endif
00047 
00048 #include <boost/function.hpp>
00049 #include <boost/bind.hpp>
00050 // PCL includes
00051 #include <pcl/pcl_base.h>
00052 #include <pcl/search/search.h>
00053 
00054 namespace pcl
00055 {
00067   inline void
00068   solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix,
00069                         const Eigen::Vector4f &point,
00070                         Eigen::Vector4f &plane_parameters, float &curvature);
00071 
00084   inline void
00085   solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix,
00086                         float &nx, float &ny, float &nz, float &curvature);
00087 
00091 
00104   template <typename PointInT, typename PointOutT>
00105   class Feature : public PCLBase<PointInT>
00106   {
00107     public:
00108       using PCLBase<PointInT>::indices_;
00109       using PCLBase<PointInT>::input_;
00110 
00111       typedef PCLBase<PointInT> BaseClass;
00112 
00113       typedef boost::shared_ptr< Feature<PointInT, PointOutT> > Ptr;
00114       typedef boost::shared_ptr< const Feature<PointInT, PointOutT> > ConstPtr;
00115 
00116       typedef typename pcl::search::Search<PointInT> KdTree;
00117       typedef typename pcl::search::Search<PointInT>::Ptr KdTreePtr;
00118 
00119       typedef pcl::PointCloud<PointInT> PointCloudIn;
00120       typedef typename PointCloudIn::Ptr PointCloudInPtr;
00121       typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00122 
00123       typedef pcl::PointCloud<PointOutT> PointCloudOut;
00124 
00125       typedef boost::function<int (size_t, double, std::vector<int> &, std::vector<float> &)> SearchMethod;
00126       typedef boost::function<int (const PointCloudIn &cloud, size_t index, double, std::vector<int> &, std::vector<float> &)> SearchMethodSurface;
00127 
00128     public:
00130       Feature () :
00131         feature_name_ (), search_method_surface_ (),
00132         surface_(), tree_(),
00133         search_parameter_(0), search_radius_(0), k_(0),
00134         fake_surface_(false)
00135       {}
00136             
00138       virtual ~Feature () {}
00139 
00147       inline void
00148       setSearchSurface (const PointCloudInConstPtr &cloud)
00149       {
00150         surface_ = cloud;
00151         fake_surface_ = false;
00152         //use_surface_  = true;
00153       }
00154 
00156       inline PointCloudInConstPtr
00157       getSearchSurface () const
00158       {
00159         return (surface_);
00160       }
00161 
00165       inline void
00166       setSearchMethod (const KdTreePtr &tree) { tree_ = tree; }
00167 
00169       inline KdTreePtr
00170       getSearchMethod () const
00171       {
00172         return (tree_);
00173       }
00174 
00176       inline double
00177       getSearchParameter () const
00178       {
00179         return (search_parameter_);
00180       }
00181 
00185       inline void
00186       setKSearch (int k) { k_ = k; }
00187 
00189       inline int
00190       getKSearch () const
00191       {
00192         return (k_);
00193       }
00194 
00199       inline void
00200       setRadiusSearch (double radius)
00201       {
00202         search_radius_ = radius;
00203       }
00204 
00206       inline double
00207       getRadiusSearch () const
00208       {
00209         return (search_radius_);
00210       }
00211 
00217       void
00218       compute (PointCloudOut &output);
00219 
00220     protected:
00222       std::string feature_name_;
00223 
00225       SearchMethodSurface search_method_surface_;
00226 
00230       PointCloudInConstPtr surface_;
00231 
00233       KdTreePtr tree_;
00234 
00236       double search_parameter_;
00237 
00239       double search_radius_;
00240 
00242       int k_;
00243 
00245       inline const std::string&
00246       getClassName () const { return (feature_name_); }
00247 
00249       virtual bool
00250       initCompute ();
00251 
00253       virtual bool
00254       deinitCompute ();
00255 
00257       bool fake_surface_;
00258 
00269       inline int
00270       searchForNeighbors (size_t index, double parameter,
00271                           std::vector<int> &indices, std::vector<float> &distances) const
00272       {
00273         return (search_method_surface_ (*input_, index, parameter, indices, distances));
00274       }
00275 
00287       inline int
00288       searchForNeighbors (const PointCloudIn &cloud, size_t index, double parameter,
00289                           std::vector<int> &indices, std::vector<float> &distances) const
00290       {
00291         return (search_method_surface_ (cloud, index, parameter, indices, distances));
00292       }
00293 
00294     private:
00298       virtual void
00299       computeFeature (PointCloudOut &output) = 0;
00300 
00301     public:
00302       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00303   };
00304 
00305 
00309   template <typename PointInT, typename PointNT, typename PointOutT>
00310   class FeatureFromNormals : public Feature<PointInT, PointOutT>
00311   {
00312     typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00313     typedef typename PointCloudIn::Ptr PointCloudInPtr;
00314     typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00315     typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00316 
00317     public:
00318       typedef typename pcl::PointCloud<PointNT> PointCloudN;
00319       typedef typename PointCloudN::Ptr PointCloudNPtr;
00320       typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00321 
00322       typedef boost::shared_ptr< FeatureFromNormals<PointInT, PointNT, PointOutT> > Ptr;
00323       typedef boost::shared_ptr< const FeatureFromNormals<PointInT, PointNT, PointOutT> > ConstPtr;
00324 
00325       // Members derived from the base class
00326       using Feature<PointInT, PointOutT>::input_;
00327       using Feature<PointInT, PointOutT>::surface_;
00328       using Feature<PointInT, PointOutT>::getClassName;
00329 
00331       FeatureFromNormals () : normals_ () {}
00332       
00334       virtual ~FeatureFromNormals () {}
00335 
00343       inline void
00344       setInputNormals (const PointCloudNConstPtr &normals) { normals_ = normals; }
00345 
00347       inline PointCloudNConstPtr
00348       getInputNormals () const { return (normals_); }
00349 
00350     protected:
00354       PointCloudNConstPtr normals_;
00355 
00357       virtual bool
00358       initCompute ();
00359 
00360     public:
00361       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00362   };
00363 
00367   template <typename PointInT, typename PointLT, typename PointOutT>
00368   class FeatureFromLabels : public Feature<PointInT, PointOutT>
00369   {
00370     typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00371     typedef typename PointCloudIn::Ptr PointCloudInPtr;
00372     typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00373 
00374     typedef typename pcl::PointCloud<PointLT> PointCloudL;
00375     typedef typename PointCloudL::Ptr PointCloudNPtr;
00376     typedef typename PointCloudL::ConstPtr PointCloudLConstPtr;
00377 
00378     typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00379 
00380     public:
00381       typedef boost::shared_ptr< FeatureFromLabels<PointInT, PointLT, PointOutT> > Ptr;
00382       typedef boost::shared_ptr< const FeatureFromLabels<PointInT, PointLT, PointOutT> > ConstPtr;
00383 
00384       // Members derived from the base class
00385       using Feature<PointInT, PointOutT>::input_;
00386       using Feature<PointInT, PointOutT>::surface_;
00387       using Feature<PointInT, PointOutT>::getClassName;
00388       using Feature<PointInT, PointOutT>::k_;
00389 
00391       FeatureFromLabels () : labels_ ()
00392       {
00393         k_ = 1; // Search tree is not always used here.
00394       }
00395       
00397       virtual ~FeatureFromLabels () {}
00398 
00405       inline void
00406       setInputLabels (const PointCloudLConstPtr &labels)
00407       {
00408         labels_ = labels;
00409       }
00410 
00412       inline PointCloudLConstPtr
00413       getInputLabels () const
00414       {
00415         return (labels_);
00416       }
00417 
00418     protected:
00422       PointCloudLConstPtr labels_;
00423 
00425       virtual bool
00426       initCompute ();
00427 
00428     public:
00429       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00430   };
00431 
00435 
00446   template <typename PointInT, typename PointRFT>
00447   class FeatureWithLocalReferenceFrames
00448   {
00449     public:
00450       typedef pcl::PointCloud<PointRFT> PointCloudLRF;
00451       typedef typename PointCloudLRF::Ptr PointCloudLRFPtr;
00452       typedef typename PointCloudLRF::ConstPtr PointCloudLRFConstPtr;
00453 
00455       FeatureWithLocalReferenceFrames () : frames_ (), frames_never_defined_ (true) {}
00456 
00458       virtual ~FeatureWithLocalReferenceFrames () {}
00459 
00466       inline void
00467       setInputReferenceFrames (const PointCloudLRFConstPtr &frames)
00468       {
00469         frames_ = frames;
00470         frames_never_defined_ = false;
00471       }
00472 
00474       inline PointCloudLRFConstPtr
00475       getInputReferenceFrames () const
00476       {
00477         return (frames_);
00478       }
00479 
00480     protected:
00482       PointCloudLRFConstPtr frames_;
00484       bool frames_never_defined_;
00485 
00491       typedef typename Feature<PointInT, PointRFT>::Ptr LRFEstimationPtr;
00492       virtual bool
00493       initLocalReferenceFrames (const size_t& indices_size,
00494                                 const LRFEstimationPtr& lrf_estimation = LRFEstimationPtr());
00495   };
00496 }
00497 
00498 #include <pcl/features/impl/feature.hpp>
00499 
00500 #endif  //#ifndef PCL_FEATURE_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:01