filter.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, 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 the copyright holder(s) 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$
00035  *
00036  */
00037 
00038 #ifndef PCL_FILTERS_IMPL_FILTER_H_
00039 #define PCL_FILTERS_IMPL_FILTER_H_
00040 
00041 #include <pcl/pcl_macros.h>
00042 #include <pcl/filters/filter.h>
00043 
00045 template <typename PointT> void
00046 pcl::removeNaNFromPointCloud (const pcl::PointCloud<PointT> &cloud_in, 
00047                               pcl::PointCloud<PointT> &cloud_out,
00048                               std::vector<int> &index)
00049 {
00050   // If the clouds are not the same, prepare the output
00051   if (&cloud_in != &cloud_out)
00052   {
00053     cloud_out.header = cloud_in.header;
00054     cloud_out.points.resize (cloud_in.points.size ());
00055   }
00056   // Reserve enough space for the indices
00057   index.resize (cloud_in.points.size ());
00058   size_t j = 0;
00059 
00060   // If the data is dense, we don't need to check for NaN
00061   if (cloud_in.is_dense)
00062   {
00063     // Simply copy the data
00064     cloud_out = cloud_in;
00065     for (j = 0; j < cloud_out.points.size (); ++j)
00066       index[j] = static_cast<int>(j);
00067   }
00068   else
00069   {
00070     for (size_t i = 0; i < cloud_in.points.size (); ++i)
00071     {
00072       if (!pcl_isfinite (cloud_in.points[i].x) || 
00073           !pcl_isfinite (cloud_in.points[i].y) || 
00074           !pcl_isfinite (cloud_in.points[i].z))
00075         continue;
00076       cloud_out.points[j] = cloud_in.points[i];
00077       index[j] = static_cast<int>(i);
00078       j++;
00079     }
00080     if (j != cloud_in.points.size ())
00081     {
00082       // Resize to the correct size
00083       cloud_out.points.resize (j);
00084       index.resize (j);
00085     }
00086 
00087     cloud_out.height = 1;
00088     cloud_out.width  = static_cast<uint32_t>(j);
00089 
00090     // Removing bad points => dense (note: 'dense' doesn't mean 'organized')
00091     cloud_out.is_dense = true;
00092   }
00093 }
00094 
00096 template <typename PointT> void
00097 pcl::removeNaNNormalsFromPointCloud (const pcl::PointCloud<PointT> &cloud_in, 
00098                                      pcl::PointCloud<PointT> &cloud_out,
00099                                      std::vector<int> &index)
00100 {
00101   // If the clouds are not the same, prepare the output
00102   if (&cloud_in != &cloud_out)
00103   {
00104     cloud_out.header = cloud_in.header;
00105     cloud_out.points.resize (cloud_in.points.size ());
00106   }
00107   // Reserve enough space for the indices
00108   index.resize (cloud_in.points.size ());
00109   size_t j = 0;
00110 
00111   for (size_t i = 0; i < cloud_in.points.size (); ++i)
00112   {
00113     if (!pcl_isfinite (cloud_in.points[i].normal_x) || 
00114         !pcl_isfinite (cloud_in.points[i].normal_y) || 
00115         !pcl_isfinite (cloud_in.points[i].normal_z))
00116       continue;
00117     cloud_out.points[j] = cloud_in.points[i];
00118     index[j] = static_cast<int>(i);
00119     j++;
00120   }
00121   if (j != cloud_in.points.size ())
00122   {
00123     // Resize to the correct size
00124     cloud_out.points.resize (j);
00125     index.resize (j);
00126   }
00127 
00128   cloud_out.height = 1;
00129   cloud_out.width  = static_cast<uint32_t>(j);
00130 }
00131 
00132 
00133 #define PCL_INSTANTIATE_removeNaNFromPointCloud(T) template PCL_EXPORTS void pcl::removeNaNFromPointCloud<T>(const pcl::PointCloud<T>&, pcl::PointCloud<T>&, std::vector<int>&);
00134 #define PCL_INSTANTIATE_removeNaNNormalsFromPointCloud(T) template PCL_EXPORTS void pcl::removeNaNNormalsFromPointCloud<T>(const pcl::PointCloud<T>&, pcl::PointCloud<T>&, std::vector<int>&);
00135 
00136 #endif    // PCL_FILTERS_IMPL_FILTER_H_
00137 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:08