mls.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) 2009-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$
00037  *
00038  */
00039 
00040 #ifndef PCL_MLS_H_
00041 #define PCL_MLS_H_
00042 
00043 // PCL includes
00044 #include <pcl/pcl_base.h>
00045 #include <pcl/search/pcl_search.h>
00046 #include <pcl/common/common.h>
00047 
00048 #include <pcl/surface/boost.h>
00049 #include <pcl/surface/eigen.h>
00050 #include <pcl/surface/processing.h>
00051 #include <map>
00052 
00053 namespace pcl
00054 {
00064   template <typename PointInT, typename PointOutT>
00065   class MovingLeastSquares: public CloudSurfaceProcessing<PointInT, PointOutT>
00066   {
00067     public:
00068       typedef boost::shared_ptr<MovingLeastSquares<PointInT, PointOutT> > Ptr;
00069       typedef boost::shared_ptr<const MovingLeastSquares<PointInT, PointOutT> > ConstPtr;
00070 
00071       using PCLBase<PointInT>::input_;
00072       using PCLBase<PointInT>::indices_;
00073       using PCLBase<PointInT>::fake_indices_;
00074       using PCLBase<PointInT>::initCompute;
00075       using PCLBase<PointInT>::deinitCompute;
00076 
00077       typedef typename pcl::search::Search<PointInT> KdTree;
00078       typedef typename pcl::search::Search<PointInT>::Ptr KdTreePtr;
00079       typedef pcl::PointCloud<pcl::Normal> NormalCloud;
00080       typedef pcl::PointCloud<pcl::Normal>::Ptr NormalCloudPtr;
00081 
00082       typedef pcl::PointCloud<PointOutT> PointCloudOut;
00083       typedef typename PointCloudOut::Ptr PointCloudOutPtr;
00084       typedef typename PointCloudOut::ConstPtr PointCloudOutConstPtr;
00085 
00086       typedef pcl::PointCloud<PointInT> PointCloudIn;
00087       typedef typename PointCloudIn::Ptr PointCloudInPtr;
00088       typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00089 
00090       typedef boost::function<int (int, double, std::vector<int> &, std::vector<float> &)> SearchMethod;
00091 
00092       enum UpsamplingMethod {NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION};
00093 
00095       MovingLeastSquares () : CloudSurfaceProcessing<PointInT, PointOutT> (),
00096                               normals_ (),
00097                               distinct_cloud_ (),
00098                               search_method_ (),
00099                               tree_ (),
00100                               order_ (2),
00101                               polynomial_fit_ (true),
00102                               search_radius_ (0.0),
00103                               sqr_gauss_param_ (0.0),
00104                               compute_normals_ (false),
00105                               upsample_method_ (NONE),
00106                               upsampling_radius_ (0.0),
00107                               upsampling_step_ (0.0),
00108                               desired_num_points_in_radius_ (0),
00109                               mls_results_ (),
00110                               voxel_size_ (1.0),
00111                               dilation_iteration_num_ (0),
00112                               nr_coeff_ (),
00113                               corresponding_input_indices_ (),
00114                               rng_alg_ (),
00115                               rng_uniform_distribution_ ()
00116                               {};
00117       
00119       virtual ~MovingLeastSquares () {}
00120 
00121 
00125       inline void
00126       setComputeNormals (bool compute_normals) { compute_normals_ = compute_normals; }
00127 
00131       inline void
00132       setSearchMethod (const KdTreePtr &tree)
00133       {
00134         tree_ = tree;
00135         // Declare the search locator definition
00136         int (KdTree::*radiusSearch)(int index, double radius, std::vector<int> &k_indices, std::vector<float> &k_sqr_distances, unsigned int max_nn) const = &KdTree::radiusSearch;
00137         search_method_ = boost::bind (radiusSearch, boost::ref (tree_), _1, _2, _3, _4, 0);
00138       }
00139 
00141       inline KdTreePtr 
00142       getSearchMethod () { return (tree_); }
00143 
00147       inline void 
00148       setPolynomialOrder (int order) { order_ = order; }
00149 
00151       inline int 
00152       getPolynomialOrder () { return (order_); }
00153 
00157       inline void 
00158       setPolynomialFit (bool polynomial_fit) { polynomial_fit_ = polynomial_fit; }
00159 
00161       inline bool 
00162       getPolynomialFit () { return (polynomial_fit_); }
00163 
00168       inline void 
00169       setSearchRadius (double radius) { search_radius_ = radius; sqr_gauss_param_ = search_radius_ * search_radius_; }
00170 
00172       inline double 
00173       getSearchRadius () { return (search_radius_); }
00174 
00179       inline void 
00180       setSqrGaussParam (double sqr_gauss_param) { sqr_gauss_param_ = sqr_gauss_param; }
00181 
00183       inline double 
00184       getSqrGaussParam () const { return (sqr_gauss_param_); }
00185 
00204       inline void
00205       setUpsamplingMethod (UpsamplingMethod method) { upsample_method_ = method; }
00206 
00208       inline void
00209       setDistinctCloud (PointCloudInConstPtr distinct_cloud) { distinct_cloud_ = distinct_cloud; }
00210 
00212       inline PointCloudInConstPtr
00213       getDistinctCloud () { return distinct_cloud_; }
00214 
00215 
00220       inline void
00221       setUpsamplingRadius (double radius) { upsampling_radius_ = radius; }
00222 
00226       inline double
00227       getUpsamplingRadius () { return upsampling_radius_; }
00228 
00233       inline void
00234       setUpsamplingStepSize (double step_size) { upsampling_step_ = step_size; }
00235 
00236 
00240       inline double
00241       getUpsamplingStepSize () { return upsampling_step_; }
00242 
00248       inline void
00249       setPointDensity (int desired_num_points_in_radius) { desired_num_points_in_radius_ = desired_num_points_in_radius; }
00250 
00251 
00255       inline int
00256       getPointDensity () { return desired_num_points_in_radius_; }
00257 
00262       inline void
00263       setDilationVoxelSize (float voxel_size) { voxel_size_ = voxel_size; }
00264 
00265 
00269       inline float
00270       getDilationVoxelSize () { return voxel_size_; }
00271 
00276       inline void
00277       setDilationIterations (int iterations) { dilation_iteration_num_ = iterations; }
00278 
00282       inline int
00283       getDilationIterations () { return dilation_iteration_num_; }
00284 
00288       void 
00289       process (PointCloudOut &output);
00290 
00291 
00294       inline PointIndicesPtr
00295       getCorrespondingIndices () { return (corresponding_input_indices_); }
00296 
00297     protected:
00299       NormalCloudPtr normals_;
00300 
00302       PointCloudInConstPtr distinct_cloud_;
00303 
00305       SearchMethod search_method_;
00306 
00308       KdTreePtr tree_;
00309 
00311       int order_;
00312 
00314       bool polynomial_fit_;
00315 
00317       double search_radius_;
00318 
00320       double sqr_gauss_param_;
00321 
00323       bool compute_normals_;
00324 
00326       UpsamplingMethod upsample_method_;
00327 
00331       double upsampling_radius_;
00332 
00336       double upsampling_step_;
00337 
00341       int desired_num_points_in_radius_;
00342 
00343       
00347       struct MLSResult
00348       {
00349         MLSResult () : mean (), plane_normal (), u_axis (), v_axis (), c_vec (), num_neighbors (), curvature (), valid (false) {}
00350 
00351         MLSResult (const Eigen::Vector3d &a_mean,
00352                    const Eigen::Vector3d &a_plane_normal,
00353                    const Eigen::Vector3d &a_u,
00354                    const Eigen::Vector3d &a_v,
00355                    const Eigen::VectorXd a_c_vec,
00356                    const int a_num_neighbors,
00357                    const float &a_curvature);
00358 
00359         Eigen::Vector3d mean, plane_normal, u_axis, v_axis;
00360         Eigen::VectorXd c_vec;
00361         int num_neighbors;
00362         float curvature;
00363         bool valid;
00364       };
00365 
00369       std::vector<MLSResult> mls_results_;
00370 
00371       
00375       class MLSVoxelGrid
00376       {
00377         public:
00378           struct Leaf { Leaf () : valid (true) {} bool valid; };
00379 
00380           MLSVoxelGrid (PointCloudInConstPtr& cloud,
00381                         IndicesPtr &indices,
00382                         float voxel_size);
00383 
00384           void
00385           dilate ();
00386 
00387           inline void
00388           getIndexIn1D (const Eigen::Vector3i &index, uint64_t &index_1d) const
00389           {
00390             index_1d = index[0] * data_size_ * data_size_ +
00391                        index[1] * data_size_ + index[2];
00392           }
00393 
00394           inline void
00395           getIndexIn3D (uint64_t index_1d, Eigen::Vector3i& index_3d) const
00396           {
00397             index_3d[0] = static_cast<Eigen::Vector3i::Scalar> (index_1d / (data_size_ * data_size_));
00398             index_1d -= index_3d[0] * data_size_ * data_size_;
00399             index_3d[1] = static_cast<Eigen::Vector3i::Scalar> (index_1d / data_size_);
00400             index_1d -= index_3d[1] * data_size_;
00401             index_3d[2] = static_cast<Eigen::Vector3i::Scalar> (index_1d);
00402           }
00403 
00404           inline void
00405           getCellIndex (const Eigen::Vector3f &p, Eigen::Vector3i& index) const
00406           {
00407             for (int i = 0; i < 3; ++i)
00408               index[i] = static_cast<Eigen::Vector3i::Scalar> ((p[i] - bounding_min_(i)) / voxel_size_);
00409           }
00410 
00411           inline void
00412           getPosition (const uint64_t &index_1d, Eigen::Vector3f &point) const
00413           {
00414             Eigen::Vector3i index_3d;
00415             getIndexIn3D (index_1d, index_3d);
00416             for (int i = 0; i < 3; ++i)
00417               point[i] = static_cast<Eigen::Vector3f::Scalar> (index_3d[i]) * voxel_size_ + bounding_min_[i];
00418           }
00419 
00420           typedef std::map<uint64_t, Leaf> HashMap;
00421           HashMap voxel_grid_;
00422           Eigen::Vector4f bounding_min_, bounding_max_;
00423           uint64_t data_size_;
00424           float voxel_size_;
00425       };
00426 
00427 
00429       float voxel_size_;
00430 
00432       int dilation_iteration_num_; 
00433 
00435       int nr_coeff_;
00436 
00438       PointIndicesPtr corresponding_input_indices_;
00439 
00445       inline int
00446       searchForNeighbors (int index, std::vector<int> &indices, std::vector<float> &sqr_distances) const
00447       {
00448         return (search_method_ (index, search_radius_, indices, sqr_distances));
00449       }
00450 
00463       void
00464       computeMLSPointNormal (int index,
00465                              const std::vector<int> &nn_indices,
00466                              std::vector<float> &nn_sqr_dists,
00467                              PointCloudOut &projected_points,
00468                              NormalCloud &projected_points_normals,
00469                              PointIndices &corresponding_input_indices,
00470                              MLSResult &mls_result) const;
00471 
00486       void
00487       projectPointToMLSSurface (float &u_disp, float &v_disp,
00488                                 Eigen::Vector3d &u_axis, Eigen::Vector3d &v_axis,
00489                                 Eigen::Vector3d &n_axis,
00490                                 Eigen::Vector3d &mean,
00491                                 float &curvature,
00492                                 Eigen::VectorXd &c_vec,
00493                                 int num_neighbors,
00494                                 PointOutT &result_point,
00495                                 pcl::Normal &result_normal) const;
00496 
00497       void
00498       copyMissingFields (const PointInT &point_in,
00499                          PointOutT &point_out) const;
00500 
00504       virtual void performProcessing (PointCloudOut &output);
00505 
00509       void performUpsampling (PointCloudOut &output);
00510 
00511     private:
00513       boost::mt19937 rng_alg_;
00514 
00518       boost::shared_ptr<boost::variate_generator<boost::mt19937&, 
00519                                                  boost::uniform_real<float> > 
00520                        > rng_uniform_distribution_;
00521 
00523       std::string getClassName () const { return ("MovingLeastSquares"); }
00524       
00525     public:
00526         EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00527   };
00528 
00529 #ifdef _OPENMP
00530 
00536   template <typename PointInT, typename PointOutT>
00537   class MovingLeastSquaresOMP: public MovingLeastSquares<PointInT, PointOutT>
00538   {
00539     public:
00540       typedef boost::shared_ptr<MovingLeastSquares<PointInT, PointOutT> > Ptr;
00541       typedef boost::shared_ptr<const MovingLeastSquares<PointInT, PointOutT> > ConstPtr;
00542 
00543       using PCLBase<PointInT>::input_;
00544       using PCLBase<PointInT>::indices_;
00545       using MovingLeastSquares<PointInT, PointOutT>::normals_;
00546       using MovingLeastSquares<PointInT, PointOutT>::corresponding_input_indices_;
00547       using MovingLeastSquares<PointInT, PointOutT>::nr_coeff_;
00548       using MovingLeastSquares<PointInT, PointOutT>::order_;
00549       using MovingLeastSquares<PointInT, PointOutT>::compute_normals_;
00550 
00551       typedef pcl::PointCloud<pcl::Normal> NormalCloud;
00552       typedef pcl::PointCloud<pcl::Normal>::Ptr NormalCloudPtr;
00553 
00554       typedef pcl::PointCloud<PointOutT> PointCloudOut;
00555       typedef typename PointCloudOut::Ptr PointCloudOutPtr;
00556       typedef typename PointCloudOut::ConstPtr PointCloudOutConstPtr;
00557 
00561       MovingLeastSquaresOMP (unsigned int threads = 0) : threads_ (threads)
00562       {
00563 
00564       }
00565 
00569       inline void
00570       setNumberOfThreads (unsigned int threads = 0)
00571       {
00572         threads_ = threads;
00573       }
00574 
00575     protected:
00579       virtual void performProcessing (PointCloudOut &output);
00580 
00582       unsigned int threads_;
00583   };
00584 #endif
00585 }
00586 
00587 #ifdef PCL_NO_PRECOMPILE
00588 #include <pcl/surface/impl/mls.hpp>
00589 #endif
00590 
00591 #endif  /* #ifndef PCL_MLS_H_ */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:39