sac_model_plane.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  * $Id: sac_model_plane.h 4915 2012-03-05 17:31:53Z rusu $
00037  *
00038  */
00039 
00040 #ifndef PCL_SAMPLE_CONSENSUS_MODEL_PLANE_H_
00041 #define PCL_SAMPLE_CONSENSUS_MODEL_PLANE_H_
00042 
00043 #include <pcl/sample_consensus/sac_model.h>
00044 #include <pcl/sample_consensus/model_types.h>
00045 
00046 namespace pcl
00047 {
00048 
00054   template <typename Point> inline void
00055   projectPoint (const Point &p, const Eigen::Vector4f &model_coefficients, Point &q)
00056   {
00057     // Calculate the distance from the point to the plane
00058     Eigen::Vector4f pp (p.x, p.y, p.z, 1);
00059     // use normalized coefficients to calculate the scalar projection 
00060     float distance_to_plane = pp.dot(model_coefficients);
00061 
00062 
00063     //TODO: Why doesn't getVector4Map work here?
00064     //Eigen::Vector4f q_e = q.getVector4fMap ();
00065     //q_e = pp - model_coefficients * distance_to_plane;
00066     
00067     Eigen::Vector4f q_e = pp - distance_to_plane * model_coefficients;
00068     q.x = q_e[0];
00069     q.y = q_e[1];
00070     q.z = q_e[2];
00071   }
00072 
00081   template <typename Point> inline double
00082   pointToPlaneDistanceSigned (const Point &p, double a, double b, double c, double d)
00083   {
00084     return (a * p.x + b * p.y + c * p.z + d);
00085   }
00086 
00092   template <typename Point> inline double
00093   pointToPlaneDistanceSigned (const Point &p, const Eigen::Vector4f &plane_coefficients)
00094   {
00095     return ( plane_coefficients[0] * p.x + plane_coefficients[1] * p.y + plane_coefficients[2] * p.z + plane_coefficients[3] );
00096   }
00097 
00106   template <typename Point> inline double
00107   pointToPlaneDistance (const Point &p, double a, double b, double c, double d)
00108   {
00109     return (fabs (pointToPlaneDistanceSigned (p, a, b, c, d)) );
00110   }
00111 
00117   template <typename Point> inline double
00118   pointToPlaneDistance (const Point &p, const Eigen::Vector4f &plane_coefficients)
00119   {
00120     return ( fabs (pointToPlaneDistanceSigned (p, plane_coefficients)) );
00121   }
00122 
00124 
00134   template <typename PointT>
00135   class SampleConsensusModelPlane : public SampleConsensusModel<PointT>
00136   {
00137     public:
00138       using SampleConsensusModel<PointT>::input_;
00139       using SampleConsensusModel<PointT>::indices_;
00140 
00141       typedef typename SampleConsensusModel<PointT>::PointCloud PointCloud;
00142       typedef typename SampleConsensusModel<PointT>::PointCloudPtr PointCloudPtr;
00143       typedef typename SampleConsensusModel<PointT>::PointCloudConstPtr PointCloudConstPtr;
00144 
00145       typedef boost::shared_ptr<SampleConsensusModelPlane> Ptr;
00146 
00150       SampleConsensusModelPlane (const PointCloudConstPtr &cloud) : SampleConsensusModel<PointT> (cloud) {};
00151 
00156       SampleConsensusModelPlane (const PointCloudConstPtr &cloud, const std::vector<int> &indices) : SampleConsensusModel<PointT> (cloud, indices) {};
00157 
00164       bool 
00165       computeModelCoefficients (const std::vector<int> &samples, 
00166                                 Eigen::VectorXf &model_coefficients);
00167 
00172       void 
00173       getDistancesToModel (const Eigen::VectorXf &model_coefficients, 
00174                            std::vector<double> &distances);
00175 
00181       void 
00182       selectWithinDistance (const Eigen::VectorXf &model_coefficients, 
00183                             const double threshold, 
00184                             std::vector<int> &inliers);
00185 
00192       virtual int
00193       countWithinDistance (const Eigen::VectorXf &model_coefficients, 
00194                            const double threshold);
00195 
00202       void 
00203       optimizeModelCoefficients (const std::vector<int> &inliers, 
00204                                  const Eigen::VectorXf &model_coefficients, 
00205                                  Eigen::VectorXf &optimized_coefficients);
00206 
00213       void 
00214       projectPoints (const std::vector<int> &inliers, 
00215                      const Eigen::VectorXf &model_coefficients, 
00216                      PointCloud &projected_points, 
00217                      bool copy_data_fields = true);
00218 
00224       bool 
00225       doSamplesVerifyModel (const std::set<int> &indices, 
00226                             const Eigen::VectorXf &model_coefficients, 
00227                             const double threshold);
00228 
00230       inline pcl::SacModel 
00231       getModelType () const { return (SACMODEL_PLANE); }
00232 
00233     protected:
00237       inline bool 
00238       isModelValid (const Eigen::VectorXf &model_coefficients)
00239       {
00240         // Needs a valid model coefficients
00241         if (model_coefficients.size () != 4)
00242         {
00243           PCL_ERROR ("[pcl::SampleConsensusModelPlane::isModelValid] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00244           return (false);
00245         }
00246         return (true);
00247       }
00248 
00249     private:
00254       virtual bool
00255       isSampleGood (const std::vector<int> &samples) const;
00256   };
00257 }
00258 
00259 #endif  //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PLANE_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:44