radius_outlier_removal.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) 2010-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: radius_outlier_removal.hpp 6144 2012-07-04 22:06:28Z rusu $
00037  *
00038  */
00039 
00040 #ifndef PCL_FILTERS_IMPL_RADIUS_OUTLIER_REMOVAL_H_
00041 #define PCL_FILTERS_IMPL_RADIUS_OUTLIER_REMOVAL_H_
00042 
00043 #include <pcl/filters/radius_outlier_removal.h>
00044 #include <pcl/common/io.h>
00045 
00047 template <typename PointT> void
00048 pcl::RadiusOutlierRemoval<PointT>::applyFilter (PointCloud &output)
00049 {
00050   std::vector<int> indices;
00051   if (keep_organized_)
00052   {
00053     bool temp = extract_removed_indices_;
00054     extract_removed_indices_ = true;
00055     applyFilterIndices (indices);
00056     extract_removed_indices_ = temp;
00057 
00058     output = *input_;
00059     for (int rii = 0; rii < static_cast<int> (removed_indices_->size ()); ++rii)  // rii = removed indices iterator
00060       output.points[(*removed_indices_)[rii]].x = output.points[(*removed_indices_)[rii]].y = output.points[(*removed_indices_)[rii]].z = user_filter_value_;
00061     if (!pcl_isfinite (user_filter_value_))
00062       output.is_dense = false;
00063   }
00064   else
00065   {
00066     applyFilterIndices (indices);
00067     copyPointCloud (*input_, indices, output);
00068   }
00069 }
00070 
00072 template <typename PointT> void
00073 pcl::RadiusOutlierRemoval<PointT>::applyFilterIndices (std::vector<int> &indices)
00074 {
00075   if (search_radius_ == 0.0)
00076   {
00077     PCL_ERROR ("[pcl::%s::applyFilter] No radius defined!\n", getClassName ().c_str ());
00078     indices.clear ();
00079     removed_indices_->clear ();
00080     return;
00081   }
00082 
00083   // Initialize the search class
00084   if (!searcher_)
00085   {
00086     if (input_->isOrganized ())
00087       searcher_.reset (new pcl::search::OrganizedNeighbor<PointT> ());
00088     else
00089       searcher_.reset (new pcl::search::KdTree<PointT> (false));
00090   }
00091   searcher_->setInputCloud (input_);
00092 
00093   // The arrays to be used
00094   std::vector<int> nn_indices (indices_->size ());
00095   std::vector<float> nn_dists (indices_->size ());
00096   indices.resize (indices_->size ());
00097   removed_indices_->resize (indices_->size ());
00098   int oii = 0, rii = 0;  // oii = output indices iterator, rii = removed indices iterator
00099 
00100   for (int iii = 0; iii < static_cast<int> (indices_->size ()); ++iii)  // iii = input indices iterator
00101   {
00102     // Perform the radius search
00103     // Note: k includes the query point, so is always at least 1
00104     int k = searcher_->radiusSearch ((*indices_)[iii], search_radius_, nn_indices, nn_dists);
00105 
00106     // Points having too few neighbors are outliers and are passed to removed indices
00107     // Unless negative was set, then it's the opposite condition
00108     if ((!negative_ && k <= min_pts_radius_) || (negative_ && k > min_pts_radius_))
00109     {
00110       if (extract_removed_indices_)
00111         (*removed_indices_)[rii++] = (*indices_)[iii];
00112       continue;
00113     }
00114 
00115     // Otherwise it was a normal point for output (inlier)
00116     indices[oii++] = (*indices_)[iii];
00117   }
00118 
00119   // Resize the output arrays
00120   indices.resize (oii);
00121   removed_indices_->resize (rii);
00122 }
00123 
00124 #define PCL_INSTANTIATE_RadiusOutlierRemoval(T) template class PCL_EXPORTS pcl::RadiusOutlierRemoval<T>;
00125 
00126 #endif  // PCL_FILTERS_IMPL_RADIUS_OUTLIER_REMOVAL_H_
00127 


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