feature.hpp
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  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: feature.hpp 6144 2012-07-04 22:06:28Z rusu $
00037  *
00038  */
00039 
00040 #ifndef PCL_FEATURES_IMPL_FEATURE_H_
00041 #define PCL_FEATURES_IMPL_FEATURE_H_
00042 
00043 #include <pcl/search/pcl_search.h>
00044 
00046 inline void
00047 pcl::solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix,
00048                            const Eigen::Vector4f &point,
00049                            Eigen::Vector4f &plane_parameters, float &curvature)
00050 {
00051   solvePlaneParameters (covariance_matrix, plane_parameters [0], plane_parameters [1], plane_parameters [2], curvature);
00052 
00053   plane_parameters[3] = 0;
00054   // Hessian form (D = nc . p_plane (centroid here) + p)
00055   plane_parameters[3] = -1 * plane_parameters.dot (point);
00056 }
00057 
00059 inline void
00060 pcl::solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix,
00061                            float &nx, float &ny, float &nz, float &curvature)
00062 {
00063   // Avoid getting hung on Eigen's optimizers
00064 //  for (int i = 0; i < 9; ++i)
00065 //    if (!pcl_isfinite (covariance_matrix.coeff (i)))
00066 //    {
00067 //      //PCL_WARN ("[pcl::solvePlaneParameteres] Covariance matrix has NaN/Inf values!\n");
00068 //      nx = ny = nz = curvature = std::numeric_limits<float>::quiet_NaN ();
00069 //      return;
00070 //    }
00071   // Extract the smallest eigenvalue and its eigenvector
00072   EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value;
00073   EIGEN_ALIGN16 Eigen::Vector3f eigen_vector;
00074   pcl::eigen33 (covariance_matrix, eigen_value, eigen_vector);
00075 
00076   nx = eigen_vector [0];
00077   ny = eigen_vector [1];
00078   nz = eigen_vector [2];
00079 
00080   // Compute the curvature surface change
00081   float eig_sum = covariance_matrix.coeff (0) + covariance_matrix.coeff (4) + covariance_matrix.coeff (8);
00082   if (eig_sum != 0)
00083     curvature = fabsf (eigen_value / eig_sum);
00084   else
00085     curvature = 0;
00086 }
00087 
00091 template <typename PointInT, typename PointOutT> bool
00092 pcl::Feature<PointInT, PointOutT>::initCompute ()
00093 {
00094   if (!PCLBase<PointInT>::initCompute ())
00095   {
00096     PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00097     return (false);
00098   }
00099 
00100   // If the dataset is empty, just return
00101   if (input_->points.empty ())
00102   {
00103     PCL_ERROR ("[pcl::%s::compute] input_ is empty!\n", getClassName ().c_str ());
00104     // Cleanup
00105     deinitCompute ();
00106     return (false);
00107   }
00108 
00109   // If no search surface has been defined, use the input dataset as the search surface itself
00110   if (!surface_)
00111   {
00112     fake_surface_ = true;
00113     surface_ = input_;
00114   }
00115 
00116   // Check if a space search locator was given
00117   if (!tree_)
00118   {
00119     if (surface_->isOrganized () && input_->isOrganized ())
00120       tree_.reset (new pcl::search::OrganizedNeighbor<PointInT> ());
00121     else
00122       tree_.reset (new pcl::search::KdTree<PointInT> (false));
00123   }
00124   
00125   if (tree_->getInputCloud () != surface_) // Make sure the tree searches the surface
00126     tree_->setInputCloud (surface_); 
00127 
00128 
00129   // Do a fast check to see if the search parameters are well defined
00130   if (search_radius_ != 0.0)
00131   {
00132     if (k_ != 0)
00133     {
00134       PCL_ERROR ("[pcl::%s::compute] ", getClassName ().c_str ());
00135       PCL_ERROR ("Both radius (%f) and K (%d) defined! ", search_radius_, k_);
00136       PCL_ERROR ("Set one of them to zero first and then re-run compute ().\n");
00137       // Cleanup
00138       deinitCompute ();
00139       return (false);
00140     }
00141     else // Use the radiusSearch () function
00142     {
00143       search_parameter_ = search_radius_;
00144       // Declare the search locator definition
00145       int (KdTree::*radiusSearchSurface)(const PointCloudIn &cloud, int index, double radius,
00146                                          std::vector<int> &k_indices, std::vector<float> &k_distances,
00147                                          unsigned int max_nn) const = &pcl::search::Search<PointInT>::radiusSearch;
00148       search_method_surface_ = boost::bind (radiusSearchSurface, boost::ref (tree_), _1, _2, _3, _4, _5, 0);
00149     }
00150   }
00151   else
00152   {
00153     if (k_ != 0) // Use the nearestKSearch () function
00154     {
00155       search_parameter_ = k_;
00156       // Declare the search locator definition
00157       int (KdTree::*nearestKSearchSurface)(const PointCloudIn &cloud, int index, int k, std::vector<int> &k_indices,
00158                                            std::vector<float> &k_distances) const = &KdTree::nearestKSearch;
00159       search_method_surface_ = boost::bind (nearestKSearchSurface, boost::ref (tree_), _1, _2, _3, _4, _5);
00160     }
00161     else
00162     {
00163       PCL_ERROR ("[pcl::%s::compute] Neither radius nor K defined! ", getClassName ().c_str ());
00164       PCL_ERROR ("Set one of them to a positive number first and then re-run compute ().\n");
00165       // Cleanup
00166       deinitCompute ();
00167       return (false);
00168     }
00169   }
00170   return (true);
00171 }
00172 
00174 template <typename PointInT, typename PointOutT> bool
00175 pcl::Feature<PointInT, PointOutT>::deinitCompute ()
00176 {
00177   // Reset the surface
00178   if (fake_surface_)
00179   {
00180     surface_.reset ();
00181     fake_surface_ = false;
00182   }
00183   return (true);
00184 }
00185 
00187 template <typename PointInT, typename PointOutT> void
00188 pcl::Feature<PointInT, PointOutT>::compute (PointCloudOut &output)
00189 {
00190   if (!initCompute ())
00191   {
00192     output.width = output.height = 0;
00193     output.points.clear ();
00194     return;
00195   }
00196 
00197   // Copy the header
00198   output.header = input_->header;
00199 
00200   // Resize the output dataset
00201   if (output.points.size () != indices_->size ())
00202     output.points.resize (indices_->size ());
00203   // Check if the output will be computed for all points or only a subset
00204   if (indices_->size () != input_->points.size ())
00205   {
00206     output.width = static_cast<int> (indices_->size ());
00207     output.height = 1;
00208   }
00209   else
00210   {
00211     output.width = input_->width;
00212     output.height = input_->height;
00213   }
00214   output.is_dense = input_->is_dense;
00215 
00216   // Perform the actual feature computation
00217   computeFeature (output);
00218 
00219   deinitCompute ();
00220 }
00221 
00223 template <typename PointInT, typename PointOutT> void
00224 pcl::Feature<PointInT, PointOutT>::computeEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
00225 {
00226   if (!initCompute ())
00227   {
00228     output.width = output.height = 0;
00229     output.points.resize (0, 0);
00230     return;
00231   }
00232 
00233   // Copy the properties
00234 //#ifndef USE_ROS
00235 //  output.properties.acquisition_time = input_->header.stamp;
00236 //#endif
00237   output.properties.sensor_origin = input_->sensor_origin_;
00238   output.properties.sensor_orientation = input_->sensor_orientation_;
00239 
00240   // Check if the output will be computed for all points or only a subset
00241   if (indices_->size () != input_->points.size ())
00242   {
00243     output.width = static_cast<int> (indices_->size ());
00244     output.height = 1;
00245   }
00246   else
00247   {
00248     output.width = input_->width;
00249     output.height = input_->height;
00250   }
00251 
00252   output.is_dense = input_->is_dense;
00253 
00254   // Perform the actual feature computation
00255   computeFeatureEigen (output);
00256 
00257   deinitCompute ();
00258 }
00259 
00263 template <typename PointInT, typename PointNT, typename PointOutT> bool
00264 pcl::FeatureFromNormals<PointInT, PointNT, PointOutT>::initCompute ()
00265 {
00266   if (!Feature<PointInT, PointOutT>::initCompute ())
00267   {
00268     PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00269     return (false);
00270   }
00271 
00272   // Check if input normals are set
00273   if (!normals_)
00274   {
00275     PCL_ERROR ("[pcl::%s::initCompute] No input dataset containing normals was given!\n", getClassName ().c_str ());
00276     Feature<PointInT, PointOutT>::deinitCompute ();
00277     return (false);
00278   }
00279 
00280   // Check if the size of normals is the same as the size of the surface
00281   if (normals_->points.size () != surface_->points.size ())
00282   {
00283     PCL_ERROR ("[pcl::%s::initCompute] ", getClassName ().c_str ());
00284     PCL_ERROR ("The number of points in the input dataset (%u) differs from ", surface_->points.size ());
00285     PCL_ERROR ("the number of points in the dataset containing the normals (%u)!\n", normals_->points.size ());
00286     Feature<PointInT, PointOutT>::deinitCompute ();
00287     return (false);
00288   }
00289 
00290   return (true);
00291 }
00292 
00296 template <typename PointInT, typename PointLT, typename PointOutT> bool
00297 pcl::FeatureFromLabels<PointInT, PointLT, PointOutT>::initCompute ()
00298 {
00299   if (!Feature<PointInT, PointOutT>::initCompute ())
00300   {
00301     PCL_ERROR ("[pcl::%s::initCompute] Init failed.\n", getClassName ().c_str ());
00302     return (false);
00303   }
00304 
00305   // Check if input normals are set
00306   if (!labels_)
00307   {
00308     PCL_ERROR ("[pcl::%s::initCompute] No input dataset containing labels was given!\n", getClassName ().c_str ());
00309     Feature<PointInT, PointOutT>::deinitCompute ();
00310     return (false);
00311   }
00312 
00313   // Check if the size of normals is the same as the size of the surface
00314   if (labels_->points.size () != surface_->points.size ())
00315   {
00316     PCL_ERROR ("[pcl::%s::initCompute] The number of points in the input dataset differs from the number of points in the dataset containing the labels!\n", getClassName ().c_str ());
00317     Feature<PointInT, PointOutT>::deinitCompute ();
00318     return (false);
00319   }
00320 
00321   return (true);
00322 }
00323 
00327 template <typename PointInT, typename PointRFT> bool
00328 pcl::FeatureWithLocalReferenceFrames<PointInT, PointRFT>::initLocalReferenceFrames (const size_t& indices_size,
00329                                                                                     const LRFEstimationPtr& lrf_estimation)
00330 {
00331   if (frames_never_defined_)
00332     frames_.reset ();
00333 
00334   // Check if input frames are set
00335   if (!frames_)
00336   {
00337     if (!lrf_estimation)
00338     {
00339       PCL_ERROR ("[initLocalReferenceFrames] No input dataset containing reference frames was given!\n");
00340       return (false);
00341     } else
00342     {
00343       //PCL_WARN ("[initLocalReferenceFrames] No input dataset containing reference frames was given! Proceed using default\n");
00344       PointCloudLRFPtr default_frames (new PointCloudLRF());
00345       lrf_estimation->compute (*default_frames);
00346       frames_ = default_frames;
00347     }
00348   }
00349 
00350   // Check if the size of frames is the same as the size of the input cloud
00351   if (frames_->points.size () != indices_size)
00352   {
00353     if (!lrf_estimation)
00354     {
00355       PCL_ERROR ("[initLocalReferenceFrames] The number of points in the input dataset differs from the number of points in the dataset containing the reference frames!\n");
00356       return (false);
00357     } else
00358     {
00359       //PCL_WARN ("[initLocalReferenceFrames] The number of points in the input dataset differs from the number of points in the dataset containing the reference frames! Proceed using default\n");
00360       PointCloudLRFPtr default_frames (new PointCloudLRF());
00361       lrf_estimation->compute (*default_frames);
00362       frames_ = default_frames;
00363     }
00364   }
00365 
00366   return (true);
00367 }
00368 
00369 #endif  //#ifndef PCL_FEATURES_IMPL_FEATURE_H_
00370 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:05