sac_model_cone.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-2012, 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  */
00038 
00039 #ifndef PCL_SAMPLE_CONSENSUS_MODEL_CONE_H_
00040 #define PCL_SAMPLE_CONSENSUS_MODEL_CONE_H_
00041 
00042 #include <pcl/sample_consensus/sac_model.h>
00043 #include <pcl/sample_consensus/model_types.h>
00044 #include <pcl/common/common.h>
00045 #include <pcl/common/distances.h>
00046 #include <limits.h>
00047 
00048 namespace pcl
00049 {
00064   template <typename PointT, typename PointNT>
00065   class SampleConsensusModelCone : public SampleConsensusModel<PointT>, public SampleConsensusModelFromNormals<PointT, PointNT>
00066   {
00067     public:
00068       using SampleConsensusModel<PointT>::input_;
00069       using SampleConsensusModel<PointT>::indices_;
00070       using SampleConsensusModel<PointT>::radius_min_;
00071       using SampleConsensusModel<PointT>::radius_max_;
00072       using SampleConsensusModelFromNormals<PointT, PointNT>::normals_;
00073       using SampleConsensusModelFromNormals<PointT, PointNT>::normal_distance_weight_;
00074       using SampleConsensusModel<PointT>::error_sqr_dists_;
00075 
00076       typedef typename SampleConsensusModel<PointT>::PointCloud PointCloud;
00077       typedef typename SampleConsensusModel<PointT>::PointCloudPtr PointCloudPtr;
00078       typedef typename SampleConsensusModel<PointT>::PointCloudConstPtr PointCloudConstPtr;
00079 
00080       typedef boost::shared_ptr<SampleConsensusModelCone> Ptr;
00081 
00086       SampleConsensusModelCone (const PointCloudConstPtr &cloud, bool random = false) 
00087         : SampleConsensusModel<PointT> (cloud, random)
00088         , SampleConsensusModelFromNormals<PointT, PointNT> ()
00089         , axis_ (Eigen::Vector3f::Zero ())
00090         , eps_angle_ (0)
00091         , min_angle_ (-std::numeric_limits<double>::max ())
00092         , max_angle_ (std::numeric_limits<double>::max ())
00093         , tmp_inliers_ ()
00094       {
00095       }
00096 
00102       SampleConsensusModelCone (const PointCloudConstPtr &cloud, 
00103                                 const std::vector<int> &indices,
00104                                 bool random = false) 
00105         : SampleConsensusModel<PointT> (cloud, indices, random)
00106         , SampleConsensusModelFromNormals<PointT, PointNT> ()
00107         , axis_ (Eigen::Vector3f::Zero ())
00108         , eps_angle_ (0)
00109         , min_angle_ (-std::numeric_limits<double>::max ())
00110         , max_angle_ (std::numeric_limits<double>::max ())
00111         , tmp_inliers_ ()
00112       {
00113       }
00114 
00118       SampleConsensusModelCone (const SampleConsensusModelCone &source) :
00119         SampleConsensusModel<PointT> (), 
00120         SampleConsensusModelFromNormals<PointT, PointNT> (),
00121         axis_ (), eps_angle_ (), min_angle_ (), max_angle_ (), tmp_inliers_ ()
00122       {
00123         *this = source;
00124       }
00125       
00127       virtual ~SampleConsensusModelCone () {}
00128 
00132       inline SampleConsensusModelCone&
00133       operator = (const SampleConsensusModelCone &source)
00134       {
00135         SampleConsensusModel<PointT>::operator=(source);
00136         axis_ = source.axis_;
00137         eps_angle_ = source.eps_angle_;
00138         min_angle_ = source.min_angle_;
00139         max_angle_ = source.max_angle_;
00140         tmp_inliers_ = source.tmp_inliers_;
00141         return (*this);
00142       }
00143 
00147       inline void 
00148       setEpsAngle (double ea) { eps_angle_ = ea; }
00149 
00151       inline double 
00152       getEpsAngle () const { return (eps_angle_); }
00153 
00157       inline void 
00158       setAxis (const Eigen::Vector3f &ax) { axis_ = ax; }
00159 
00161       inline Eigen::Vector3f 
00162       getAxis () const { return (axis_); }
00163 
00169       inline void
00170       setMinMaxOpeningAngle (const double &min_angle, const double &max_angle)
00171       {
00172         min_angle_ = min_angle;
00173         max_angle_ = max_angle;
00174       }
00175 
00180       inline void
00181       getMinMaxOpeningAngle (double &min_angle, double &max_angle) const
00182       {
00183         min_angle = min_angle_;
00184         max_angle = max_angle_;
00185       }
00186 
00193       bool 
00194       computeModelCoefficients (const std::vector<int> &samples, 
00195                                 Eigen::VectorXf &model_coefficients);
00196 
00201       void 
00202       getDistancesToModel (const Eigen::VectorXf &model_coefficients,  
00203                            std::vector<double> &distances);
00204 
00210       void 
00211       selectWithinDistance (const Eigen::VectorXf &model_coefficients, 
00212                             const double threshold, 
00213                             std::vector<int> &inliers);
00214 
00221       virtual int
00222       countWithinDistance (const Eigen::VectorXf &model_coefficients, 
00223                            const double threshold);
00224 
00225 
00232       void 
00233       optimizeModelCoefficients (const std::vector<int> &inliers, 
00234                                  const Eigen::VectorXf &model_coefficients, 
00235                                  Eigen::VectorXf &optimized_coefficients);
00236 
00237 
00244       void 
00245       projectPoints (const std::vector<int> &inliers, 
00246                      const Eigen::VectorXf &model_coefficients, 
00247                      PointCloud &projected_points, 
00248                      bool copy_data_fields = true);
00249 
00255       bool 
00256       doSamplesVerifyModel (const std::set<int> &indices, 
00257                             const Eigen::VectorXf &model_coefficients, 
00258                             const double threshold);
00259 
00261       inline pcl::SacModel 
00262       getModelType () const { return (SACMODEL_CONE); }
00263 
00264     protected:
00269       double 
00270       pointToAxisDistance (const Eigen::Vector4f &pt, const Eigen::VectorXf &model_coefficients);
00271 
00273       std::string 
00274       getName () const { return ("SampleConsensusModelCone"); }
00275 
00276     protected:
00280       bool 
00281       isModelValid (const Eigen::VectorXf &model_coefficients);
00282 
00287       bool
00288       isSampleGood (const std::vector<int> &samples) const;
00289 
00290     private:
00292       Eigen::Vector3f axis_;
00293     
00295       double eps_angle_;
00296 
00298       double min_angle_;
00299       double max_angle_;
00300 
00302       const std::vector<int> *tmp_inliers_;
00303 
00304 #if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3
00305 #pragma GCC diagnostic ignored "-Weffc++"
00306 #endif
00307 
00308       struct OptimizationFunctor : pcl::Functor<float>
00309       {
00315         OptimizationFunctor (int m_data_points, pcl::SampleConsensusModelCone<PointT, PointNT> *model) : 
00316           pcl::Functor<float> (m_data_points), model_ (model) {}
00317 
00323         int 
00324         operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const
00325         {
00326           Eigen::Vector4f apex  (x[0], x[1], x[2], 0);
00327           Eigen::Vector4f axis_dir (x[3], x[4], x[5], 0);
00328           float opening_angle = x[6];
00329 
00330           float apexdotdir = apex.dot (axis_dir);
00331           float dirdotdir = 1.0f / axis_dir.dot (axis_dir);
00332 
00333           for (int i = 0; i < values (); ++i)
00334           {
00335             // dist = f - r
00336             Eigen::Vector4f pt (model_->input_->points[(*model_->tmp_inliers_)[i]].x,
00337                                 model_->input_->points[(*model_->tmp_inliers_)[i]].y,
00338                                 model_->input_->points[(*model_->tmp_inliers_)[i]].z, 0);
00339 
00340             // Calculate the point's projection on the cone axis
00341             float k = (pt.dot (axis_dir) - apexdotdir) * dirdotdir;
00342             Eigen::Vector4f pt_proj = apex + k * axis_dir;
00343 
00344             // Calculate the actual radius of the cone at the level of the projected point
00345             Eigen::Vector4f height = apex-pt_proj;
00346             float actual_cone_radius = tanf (opening_angle) * height.norm ();
00347 
00348             fvec[i] = static_cast<float> (pcl::sqrPointToLineDistance (pt, apex, axis_dir) - actual_cone_radius * actual_cone_radius);
00349           }
00350           return (0);
00351         }
00352 
00353         pcl::SampleConsensusModelCone<PointT, PointNT> *model_;
00354       };
00355 #if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3
00356 #pragma GCC diagnostic warning "-Weffc++"
00357 #endif
00358   };
00359 }
00360 
00361 #ifdef PCL_NO_PRECOMPILE
00362 #include <pcl/sample_consensus/impl/sac_model_cone.hpp>
00363 #endif
00364 
00365 #endif  //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_CONE_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:32:16