sac_model_normal_parallel_plane.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) 2009-2010, 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  * $Id$
00038  *
00039  */
00040 
00041 #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PARALLEL_PLANE_H_
00042 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PARALLEL_PLANE_H_
00043 
00044 #include <pcl/sample_consensus/sac_model_normal_parallel_plane.h>
00045 
00047 template <typename PointT, typename PointNT> void
00048 pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>::selectWithinDistance (
00049       const Eigen::VectorXf &model_coefficients, const double threshold, std::vector<int> &inliers)
00050 {
00051   if (!normals_)
00052   {
00053     PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::selectWithinDistance] No input dataset containing normals was given!\n");
00054     return;
00055   }
00056 
00057   // Check if the model is valid given the user constraints
00058   if (!isModelValid (model_coefficients))
00059   {
00060     inliers.clear ();
00061     return;
00062   }
00063 
00064   // Obtain the plane normal
00065   Eigen::Vector4f coeff = model_coefficients;
00066 
00067   int nr_p = 0;
00068   inliers.resize (indices_->size ());
00069   error_sqr_dists_.resize (indices_->size ());
00070 
00071   // Iterate through the 3d points and calculate the distances from them to the plane
00072   for (size_t i = 0; i < indices_->size (); ++i)
00073   {
00074     // Calculate the distance from the point to the plane normal as the dot product
00075     // D = (P-A).N/|N|
00076     Eigen::Vector4f p (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 1);
00077     Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00078     double d_euclid = fabs (coeff.dot (p));
00079 
00080     // Calculate the angular distance between the point normal and the plane normal
00081     double d_normal = getAngle3D (n, coeff);
00082     d_normal = (std::min) (d_normal, fabs(M_PI - d_normal));
00083 
00084     double distance = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid); 
00085     if (distance < threshold)
00086     {
00087       // Returns the indices of the points whose distances are smaller than the threshold
00088       inliers[nr_p] = (*indices_)[i];
00089       error_sqr_dists_[nr_p] = distance;
00090       ++nr_p;
00091     }
00092   }
00093   inliers.resize (nr_p);
00094   error_sqr_dists_.resize (nr_p);
00095 }
00096 
00098 template <typename PointT, typename PointNT> int
00099 pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>::countWithinDistance (
00100       const Eigen::VectorXf &model_coefficients, const double threshold)
00101 {
00102   if (!normals_)
00103   {
00104     PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::countWithinDistance] No input dataset containing normals was given!\n");
00105     return (0);
00106   }
00107 
00108   // Check if the model is valid given the user constraints
00109   if (!isModelValid (model_coefficients))
00110     return (0);
00111 
00112   // Obtain the plane normal
00113   Eigen::Vector4f coeff = model_coefficients;
00114 
00115   int nr_p = 0;
00116 
00117   // Iterate through the 3d points and calculate the distances from them to the plane
00118   for (size_t i = 0; i < indices_->size (); ++i)
00119   {
00120     // Calculate the distance from the point to the plane normal as the dot product
00121     // D = (P-A).N/|N|
00122     Eigen::Vector4f p (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 1);
00123     Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00124     double d_euclid = fabs (coeff.dot (p));
00125 
00126     // Calculate the angular distance between the point normal and the plane normal
00127     double d_normal = fabs (getAngle3D (n, coeff));
00128     d_normal = (std::min) (d_normal, fabs(M_PI - d_normal));
00129 
00130     if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold)
00131       nr_p++;
00132   }
00133   return (nr_p);
00134 }
00135 
00136 
00138 template <typename PointT, typename PointNT> void
00139 pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>::getDistancesToModel (
00140       const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00141 {
00142   if (!normals_)
00143   {
00144     PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::getDistancesToModel] No input dataset containing normals was given!\n");
00145     return;
00146   }
00147 
00148   // Check if the model is valid given the user constraints
00149   if (!isModelValid (model_coefficients))
00150   {
00151     distances.clear ();
00152     return;
00153   }
00154 
00155   // Obtain the plane normal
00156   Eigen::Vector4f coeff = model_coefficients;
00157 
00158   distances.resize (indices_->size ());
00159 
00160   // Iterate through the 3d points and calculate the distances from them to the plane
00161   for (size_t i = 0; i < indices_->size (); ++i)
00162   {
00163     // Calculate the distance from the point to the plane normal as the dot product
00164     // D = (P-A).N/|N|
00165     Eigen::Vector4f p (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 1);
00166     Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00167     double d_euclid = fabs (coeff.dot (p));
00168 
00169     // Calculate the angular distance between the point normal and the plane normal
00170     double d_normal = getAngle3D (n, coeff);
00171     d_normal = (std::min) (d_normal, fabs (M_PI - d_normal));
00172 
00173     distances[i] = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid);
00174   }
00175 }
00176 
00178 template <typename PointT, typename PointNT> bool
00179 pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>::isModelValid (const Eigen::VectorXf &model_coefficients)
00180 {
00181   // Needs a valid model coefficients
00182   if (model_coefficients.size () != 4)
00183   {
00184     PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::isModelValid] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00185     return (false);
00186   }
00187 
00188   // Check against template, if given
00189   if (eps_angle_ > 0.0)
00190   {
00191     // Obtain the plane normal
00192     Eigen::Vector4f coeff = model_coefficients;
00193     coeff[3] = 0;
00194     coeff.normalize ();
00195 
00196     if (fabs (axis_.dot (coeff)) < cos_angle_)
00197       return  (false);
00198   }
00199 
00200   if (eps_dist_ > 0.0)
00201   {
00202     if (fabs (-model_coefficients[3] - distance_from_origin_) > eps_dist_)
00203       return (false);
00204   }
00205 
00206   return (true);
00207 }
00208 
00209 #define PCL_INSTANTIATE_SampleConsensusModelNormalParallelPlane(PointT, PointNT) template class PCL_EXPORTS pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>;
00210 
00211 #endif    // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PARALLEL_PLANE_H_
00212 
00213 


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