integral_image_normal.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  *
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  */
00037 
00038 #ifndef PCL_INTEGRALIMAGE_BASED_NORMAL_ESTIMATOR_H_
00039 #define PCL_INTEGRALIMAGE_BASED_NORMAL_ESTIMATOR_H_
00040 
00041 #include <pcl/point_cloud.h>
00042 #include <pcl/point_types.h>
00043 #include <pcl/features/feature.h>
00044 #include <pcl/features/integral_image2D.h>
00045 
00046 #if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3
00047 #pragma GCC diagnostic ignored "-Weffc++"
00048 #endif
00049 namespace pcl
00050 {
00054   template <typename PointInT, typename PointOutT>
00055   class IntegralImageNormalEstimation: public Feature<PointInT, PointOutT>
00056   {
00057     using Feature<PointInT, PointOutT>::input_;
00058     using Feature<PointInT, PointOutT>::feature_name_;
00059     using Feature<PointInT, PointOutT>::tree_;
00060     using Feature<PointInT, PointOutT>::k_;
00061 
00062     public:
00063 
00065         enum BorderPolicy
00066         {
00067           BORDER_POLICY_IGNORE,
00068           BORDER_POLICY_MIRROR
00069         };
00070 
00082       enum NormalEstimationMethod
00083       {
00084         COVARIANCE_MATRIX,
00085         AVERAGE_3D_GRADIENT,
00086         AVERAGE_DEPTH_CHANGE,
00087         SIMPLE_3D_GRADIENT
00088       };
00089 
00090       typedef typename Feature<PointInT, PointOutT>::PointCloudIn  PointCloudIn;
00091       typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00092 
00094       IntegralImageNormalEstimation ()
00095         : normal_estimation_method_(AVERAGE_3D_GRADIENT)
00096         , border_policy_ (BORDER_POLICY_IGNORE)
00097         , rect_width_ (0), rect_width_2_ (0), rect_width_4_ (0)
00098         , rect_height_ (0), rect_height_2_ (0), rect_height_4_ (0)
00099         , distance_threshold_ (0)
00100         , integral_image_DX_ (false)
00101         , integral_image_DY_ (false)
00102         , integral_image_depth_ (false)
00103         , integral_image_XYZ_ (true)
00104         , diff_x_ (NULL)
00105         , diff_y_ (NULL)
00106         , depth_data_ (NULL)
00107         , distance_map_ (NULL)
00108         , use_depth_dependent_smoothing_ (false)
00109         , max_depth_change_factor_ (20.0f*0.001f)
00110         , normal_smoothing_size_ (10.0f)
00111         , init_covariance_matrix_ (false)
00112         , init_average_3d_gradient_ (false)
00113         , init_simple_3d_gradient_ (false)
00114         , init_depth_change_ (false)
00115         , vpx_ (0.0f)
00116         , vpy_ (0.0f)
00117         , vpz_ (0.0f)
00118         , use_sensor_origin_ (true)
00119       {
00120         feature_name_ = "IntegralImagesNormalEstimation";
00121         tree_.reset ();
00122         k_ = 1;
00123       }
00124 
00126       virtual ~IntegralImageNormalEstimation ();
00127 
00132       void
00133       setRectSize (const int width, const int height);
00134 
00138       void
00139       setBorderPolicy (const BorderPolicy border_policy)
00140       {
00141         border_policy_ = border_policy;
00142       }
00143 
00150       void
00151       computePointNormal (const int pos_x, const int pos_y, const unsigned point_index, PointOutT &normal);
00152 
00159       void
00160       computePointNormalMirror (const int pos_x, const int pos_y, const unsigned point_index, PointOutT &normal);
00161 
00166       void
00167       setMaxDepthChangeFactor (float max_depth_change_factor)
00168       {
00169         max_depth_change_factor_ = max_depth_change_factor;
00170       }
00171 
00176       void
00177       setNormalSmoothingSize (float normal_smoothing_size)
00178       {
00179         normal_smoothing_size_ = normal_smoothing_size;
00180       }
00181 
00194       void
00195       setNormalEstimationMethod (NormalEstimationMethod normal_estimation_method)
00196       {
00197         normal_estimation_method_ = normal_estimation_method;
00198       }
00199 
00203       void
00204       setDepthDependentSmoothing (bool use_depth_dependent_smoothing)
00205       {
00206         use_depth_dependent_smoothing_ = use_depth_dependent_smoothing;
00207       }
00208 
00212       virtual inline void
00213       setInputCloud (const typename PointCloudIn::ConstPtr &cloud)
00214       {
00215         input_ = cloud;
00216         if (!cloud->isOrganized ())
00217         {
00218           PCL_ERROR ("[pcl::IntegralImageNormalEstimation::setInputCloud] Input dataset is not organized (height = 1).\n");
00219           return;
00220         }
00221 
00222         init_covariance_matrix_ = init_average_3d_gradient_ = init_depth_change_ = false;
00223         
00224         if (use_sensor_origin_)
00225         {
00226           vpx_ = input_->sensor_origin_.coeff (0);
00227           vpy_ = input_->sensor_origin_.coeff (1);
00228           vpz_ = input_->sensor_origin_.coeff (2);
00229         }
00230 
00231         // Initialize the correct data structure based on the normal estimation method chosen
00232         initData ();
00233       }
00234 
00237       inline float*
00238       getDistanceMap ()
00239       {
00240         return (distance_map_);
00241       }
00242 
00248       inline void
00249       setViewPoint (float vpx, float vpy, float vpz)
00250       {
00251         vpx_ = vpx;
00252         vpy_ = vpy;
00253         vpz_ = vpz;
00254         use_sensor_origin_ = false;
00255       }
00256 
00265       inline void
00266       getViewPoint (float &vpx, float &vpy, float &vpz)
00267       {
00268         vpx = vpx_;
00269         vpy = vpy_;
00270         vpz = vpz_;
00271       }
00272 
00277       inline void
00278       useSensorOriginAsViewPoint ()
00279       {
00280         use_sensor_origin_ = true;
00281         if (input_)
00282         {
00283           vpx_ = input_->sensor_origin_.coeff (0);
00284           vpy_ = input_->sensor_origin_.coeff (1);
00285           vpz_ = input_->sensor_origin_.coeff (2);
00286         }
00287         else
00288         {
00289           vpx_ = 0;
00290           vpy_ = 0;
00291           vpz_ = 0;
00292         }
00293       }
00294       
00295     protected:
00296 
00300       void
00301       computeFeature (PointCloudOut &output);
00302 
00304       void
00305       initData ();
00306 
00307     private:
00314       NormalEstimationMethod normal_estimation_method_;
00315 
00317       BorderPolicy border_policy_;
00318 
00320       int rect_width_;
00321       int rect_width_2_;
00322       int rect_width_4_;
00324       int rect_height_;
00325       int rect_height_2_;
00326       int rect_height_4_;
00327 
00329       float distance_threshold_;
00330 
00332       IntegralImage2D<float, 3> integral_image_DX_;
00334       IntegralImage2D<float, 3> integral_image_DY_;
00336       IntegralImage2D<float, 1> integral_image_depth_;
00338       IntegralImage2D<float, 3> integral_image_XYZ_;
00339 
00341       float *diff_x_;
00343       float *diff_y_;
00344 
00346       float *depth_data_;
00347 
00349       float *distance_map_;
00350 
00352       bool use_depth_dependent_smoothing_;
00353 
00355       float max_depth_change_factor_;
00356 
00358       float normal_smoothing_size_;
00359 
00361       bool init_covariance_matrix_;
00362 
00364       bool init_average_3d_gradient_;
00365 
00367       bool init_simple_3d_gradient_;
00368 
00370       bool init_depth_change_;
00371 
00374       float vpx_, vpy_, vpz_;
00375 
00377       bool use_sensor_origin_;
00378       
00380       bool
00381       initCompute ();
00382 
00384       void
00385       initCovarianceMatrixMethod ();
00386 
00388       void
00389       initAverage3DGradientMethod ();
00390 
00392       void
00393       initAverageDepthChangeMethod ();
00394 
00396       void
00397       initSimple3DGradientMethod ();
00398 
00399     private:
00403       void
00404       computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &) {}
00405     public:
00406       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00407   };
00408 }
00409 #if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3
00410 #pragma GCC diagnostic warning "-Weffc++"
00411 #endif
00412 
00413 
00414 #endif
00415 


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