sac_model_normal_sphere.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-2012, 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_normal_sphere.hpp schrandt $
00037  *
00038  */
00039 
00040 #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_SPHERE_H_
00041 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_SPHERE_H_
00042 
00043 #include <pcl/sample_consensus/sac_model_normal_sphere.h>
00044 
00046 template <typename PointT, typename PointNT> void
00047 pcl::SampleConsensusModelNormalSphere<PointT, PointNT>::selectWithinDistance (
00048       const Eigen::VectorXf &model_coefficients, const double threshold, std::vector<int> &inliers)
00049 {
00050   if (!normals_)
00051   {
00052     PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::selectWithinDistance] No input dataset containing normals was given!\n");
00053     inliers.clear ();
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 sphere center
00065   Eigen::Vector4f center = model_coefficients;
00066   center[3] = 0;
00067 
00068   int nr_p = 0;
00069   inliers.resize (indices_->size ());
00070   // Iterate through the 3d points and calculate the distances from them to the plane
00071   for (size_t i = 0; i < indices_->size (); ++i)
00072   {
00073     // Calculate the distance from the point to the sphere center as the difference between
00074     // dist(point,sphere_origin) and sphere_radius
00075     Eigen::Vector4f p (input_->points[(*indices_)[i]].x, 
00076                        input_->points[(*indices_)[i]].y,
00077                        input_->points[(*indices_)[i]].z, 
00078                        0);
00079 
00080     Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], 
00081                        normals_->points[(*indices_)[i]].normal[1], 
00082                        normals_->points[(*indices_)[i]].normal[2], 
00083                        0);
00084 
00085     Eigen::Vector4f n_dir = p - center;
00086     double d_euclid = fabs (n_dir.norm () - model_coefficients[3]);
00087 
00088     // Calculate the angular distance between the point normal and the plane normal
00089     double d_normal = fabs (getAngle3D (n, n_dir));
00090     d_normal = (std::min) (d_normal, M_PI - d_normal);
00091 
00092     if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold)
00093     {
00094       // Returns the indices of the points whose distances are smaller than the threshold
00095       inliers[nr_p] = (*indices_)[i];
00096       nr_p++;
00097     }
00098   }
00099   inliers.resize (nr_p);
00100 }
00101 
00103 template <typename PointT, typename PointNT> int
00104 pcl::SampleConsensusModelNormalSphere<PointT, PointNT>::countWithinDistance (
00105       const Eigen::VectorXf &model_coefficients,  const double threshold)
00106 {
00107   if (!normals_)
00108   {
00109     PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given!\n");
00110     return (0);
00111   }
00112 
00113   // Check if the model is valid given the user constraints
00114   if (!isModelValid (model_coefficients))
00115     return(0);
00116 
00117 
00118   // Obtain the shpere centroid
00119   Eigen::Vector4f center = model_coefficients;
00120   center[3] = 0;
00121 
00122   int nr_p = 0;
00123 
00124   // Iterate through the 3d points and calculate the distances from them to the plane
00125   for (size_t i = 0; i < indices_->size (); ++i)
00126   {
00127     // Calculate the distance from the point to the sphere centroid as the difference between
00128     // dist(point,sphere_origin) and sphere_radius
00129     Eigen::Vector4f p (input_->points[(*indices_)[i]].x, 
00130                        input_->points[(*indices_)[i]].y, 
00131                        input_->points[(*indices_)[i]].z, 
00132                        0);
00133 
00134     Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], 
00135                        normals_->points[(*indices_)[i]].normal[1], 
00136                        normals_->points[(*indices_)[i]].normal[2], 
00137                        0);
00138 
00139     Eigen::Vector4f n_dir = (p-center);
00140     double d_euclid = fabs (n_dir.norm () - model_coefficients[3]);
00141     //
00142     // Calculate the angular distance between the point normal and the plane normal
00143     double d_normal = fabs (getAngle3D (n, n_dir));
00144     d_normal = (std::min) (d_normal, M_PI - d_normal);
00145 
00146     if (fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid) < threshold)
00147       nr_p++;
00148   }
00149   return (nr_p);
00150 }
00151 
00153 template <typename PointT, typename PointNT> void
00154 pcl::SampleConsensusModelNormalSphere<PointT, PointNT>::getDistancesToModel (
00155       const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00156 {
00157   if (!normals_)
00158   {
00159     PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given!\n");
00160     return;
00161   }
00162 
00163   // Check if the model is valid given the user constraints
00164   if (!isModelValid (model_coefficients))
00165   {
00166     distances.clear ();
00167     return;
00168   }
00169 
00170   // Obtain the sphere centroid
00171   Eigen::Vector4f center = model_coefficients;
00172   center[3] = 0;
00173 
00174   distances.resize (indices_->size ());
00175 
00176   // Iterate through the 3d points and calculate the distances from them to the plane
00177   for (size_t i = 0; i < indices_->size (); ++i)
00178   {
00179     // Calculate the distance from the point to the sphere as the difference between
00180     // dist(point,sphere_origin) and sphere_radius
00181     Eigen::Vector4f p (input_->points[(*indices_)[i]].x, 
00182                        input_->points[(*indices_)[i]].y, 
00183                        input_->points[(*indices_)[i]].z, 
00184                        0);
00185 
00186     Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], 
00187                        normals_->points[(*indices_)[i]].normal[1], 
00188                        normals_->points[(*indices_)[i]].normal[2], 
00189                        0);
00190 
00191     Eigen::Vector4f n_dir = (p-center);
00192     double d_euclid = fabs (n_dir.norm () - model_coefficients[3]);
00193     //
00194     // Calculate the angular distance between the point normal and the plane normal
00195     double d_normal = fabs (getAngle3D (n, n_dir));
00196     d_normal = (std::min) (d_normal, M_PI - d_normal);
00197 
00198     distances[i] = fabs (normal_distance_weight_ * d_normal + (1 - normal_distance_weight_) * d_euclid);
00199   }
00200 }
00201 
00203 template <typename PointT, typename PointNT> bool 
00204 pcl::SampleConsensusModelNormalSphere<PointT, PointNT>::isModelValid (const Eigen::VectorXf &model_coefficients)
00205 {
00206   // Needs a valid model coefficients
00207   if (model_coefficients.size () != 4)
00208   {
00209     PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::selectWithinDistance] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00210     return (false);
00211   }
00212 
00213   if (radius_min_ != -std::numeric_limits<double>::max() && model_coefficients[3] < radius_min_)
00214     return (false);
00215   if (radius_max_ != std::numeric_limits<double>::max() && model_coefficients[3] > radius_max_)
00216     return (false);
00217 
00218   return (true);
00219 }
00220 
00221 #define PCL_INSTANTIATE_SampleConsensusModelNormalSphere(PointT, PointNT) template class PCL_EXPORTS pcl::SampleConsensusModelNormalSphere<PointT, PointNT>;
00222 
00223 #endif    // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_SPHERE_H_
00224 


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