sac_model_normal_parallel_plane.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009-2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: sac_model_normal_parallel_plane.hpp 5026 2012-03-12 02:51:44Z rusu $
00035  *
00036  */
00037 
00038 #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PARALLEL_PLANE_H_
00039 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PARALLEL_PLANE_H_
00040 
00041 #include <pcl/sample_consensus/sac_model_normal_parallel_plane.h>
00042 
00044 template <typename PointT, typename PointNT> void
00045 pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>::selectWithinDistance (
00046       const Eigen::VectorXf &model_coefficients, const double threshold, std::vector<int> &inliers)
00047 {
00048   if (!normals_)
00049   {
00050     PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::selectWithinDistance] No input dataset containing normals was given!\n");
00051     return;
00052   }
00053 
00054   // Check if the model is valid given the user constraints
00055   if (!isModelValid (model_coefficients))
00056   {
00057     inliers.clear ();
00058     return;
00059   }
00060 
00061   // Obtain the plane normal
00062   Eigen::Vector4f coeff = model_coefficients;
00063 
00064   int nr_p = 0;
00065   inliers.resize (indices_->size ());
00066   // Iterate through the 3d points and calculate the distances from them to the plane
00067   for (size_t i = 0; i < indices_->size (); ++i)
00068   {
00069     // Calculate the distance from the point to the plane normal as the dot product
00070     // D = (P-A).N/|N|
00071     Eigen::Vector4f p (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 1);
00072     Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00073     double d_euclid = fabs (coeff.dot (p));
00074 
00075     // Calculate the angular distance between the point normal and the plane normal
00076     double d_normal = getAngle3D (n, coeff);
00077     d_normal = (std::min) (d_normal, fabs(M_PI - d_normal));
00078 
00079     if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold)
00080     {
00081       // Returns the indices of the points whose distances are smaller than the threshold
00082       inliers[nr_p] = (*indices_)[i];
00083       nr_p++;
00084     }
00085   }
00086   inliers.resize (nr_p);
00087 }
00088 
00090 template <typename PointT, typename PointNT> int
00091 pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>::countWithinDistance (
00092       const Eigen::VectorXf &model_coefficients, const double threshold)
00093 {
00094   if (!normals_)
00095   {
00096     PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::countWithinDistance] No input dataset containing normals was given!\n");
00097     return (0);
00098   }
00099 
00100   // Check if the model is valid given the user constraints
00101   if (!isModelValid (model_coefficients))
00102     return (0);
00103 
00104   // Obtain the plane normal
00105   Eigen::Vector4f coeff = model_coefficients;
00106 
00107   int nr_p = 0;
00108 
00109   // Iterate through the 3d points and calculate the distances from them to the plane
00110   for (size_t i = 0; i < indices_->size (); ++i)
00111   {
00112     // Calculate the distance from the point to the plane normal as the dot product
00113     // D = (P-A).N/|N|
00114     Eigen::Vector4f p (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 1);
00115     Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00116     double d_euclid = fabs (coeff.dot (p));
00117 
00118     // Calculate the angular distance between the point normal and the plane normal
00119     double d_normal = fabs (getAngle3D (n, coeff));
00120     d_normal = (std::min) (d_normal, fabs(M_PI - d_normal));
00121 
00122     if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold)
00123       nr_p++;
00124   }
00125   return (nr_p);
00126 }
00127 
00128 
00130 template <typename PointT, typename PointNT> void
00131 pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>::getDistancesToModel (
00132       const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00133 {
00134   if (!normals_)
00135   {
00136     PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::getDistancesToModel] No input dataset containing normals was given!\n");
00137     return;
00138   }
00139 
00140   // Check if the model is valid given the user constraints
00141   if (!isModelValid (model_coefficients))
00142   {
00143     distances.clear ();
00144     return;
00145   }
00146 
00147   // Obtain the plane normal
00148   Eigen::Vector4f coeff = model_coefficients;
00149 
00150   distances.resize (indices_->size ());
00151 
00152   // Iterate through the 3d points and calculate the distances from them to the plane
00153   for (size_t i = 0; i < indices_->size (); ++i)
00154   {
00155     // Calculate the distance from the point to the plane normal as the dot product
00156     // D = (P-A).N/|N|
00157     Eigen::Vector4f p (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 1);
00158     Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0);
00159     double d_euclid = fabs (coeff.dot (p));
00160 
00161     // Calculate the angular distance between the point normal and the plane normal
00162     double d_normal = getAngle3D (n, coeff);
00163     d_normal = (std::min) (d_normal, fabs (M_PI - d_normal));
00164 
00165     distances[i] = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid);
00166   }
00167 }
00168 
00170 template <typename PointT, typename PointNT> bool
00171 pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>::isModelValid (const Eigen::VectorXf &model_coefficients)
00172 {
00173   // Needs a valid model coefficients
00174   if (model_coefficients.size () != 4)
00175   {
00176     PCL_ERROR ("[pcl::SampleConsensusModelNormalParallelPlane::isModelValid] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00177     return (false);
00178   }
00179 
00180   // Check against template, if given
00181   if (eps_angle_ > 0.0)
00182   {
00183     // Obtain the plane normal
00184     Eigen::Vector4f coeff = model_coefficients;
00185     coeff[3] = 0;
00186     coeff.normalize ();
00187 
00188     if (fabs (axis_.dot (coeff)) < cos_angle_)
00189       return  (false);
00190   }
00191 
00192   if (eps_dist_ > 0.0)
00193   {
00194     if (fabs (-model_coefficients[3] - distance_from_origin_) > eps_dist_)
00195       return (false);
00196   }
00197 
00198   return (true);
00199 }
00200 
00201 #define PCL_INSTANTIATE_SampleConsensusModelNormalParallelPlane(PointT, PointNT) template class PCL_EXPORTS pcl::SampleConsensusModelNormalParallelPlane<PointT, PointNT>;
00202 
00203 #endif    // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PARALLEL_PLANE_H_
00204 
00205 


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