voxel_grid.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 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: voxel_grid.hpp 6144 2012-07-04 22:06:28Z rusu $
00035  *
00036  */
00037 
00038 #ifndef PCL_FILTERS_IMPL_VOXEL_GRID_H_
00039 #define PCL_FILTERS_IMPL_VOXEL_GRID_H_
00040 
00041 #include <pcl/common/common.h>
00042 #include <pcl/filters/voxel_grid.h>
00043 
00045 template <typename PointT> void
00046 pcl::getMinMax3D (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00047                   const std::string &distance_field_name, float min_distance, float max_distance,
00048                   Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative)
00049 {
00050   Eigen::Array4f min_p, max_p;
00051   min_p.setConstant (FLT_MAX);
00052   max_p.setConstant (-FLT_MAX);
00053 
00054   // Get the fields list and the distance field index
00055   std::vector<sensor_msgs::PointField> fields;
00056   int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name, fields);
00057 
00058   float distance_value;
00059   // If dense, no need to check for NaNs
00060   if (cloud->is_dense)
00061   {
00062     for (size_t i = 0; i < cloud->points.size (); ++i)
00063     {
00064       // Get the distance value
00065       const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&cloud->points[i]);
00066       memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float));
00067 
00068       if (limit_negative)
00069       {
00070         // Use a threshold for cutting out points which inside the interval
00071         if ((distance_value < max_distance) && (distance_value > min_distance))
00072           continue;
00073       }
00074       else
00075       {
00076         // Use a threshold for cutting out points which are too close/far away
00077         if ((distance_value > max_distance) || (distance_value < min_distance))
00078           continue;
00079       }
00080       // Create the point structure and get the min/max
00081       pcl::Array4fMapConst pt = cloud->points[i].getArray4fMap ();
00082       min_p = min_p.min (pt);
00083       max_p = max_p.max (pt);
00084     }
00085   }
00086   else
00087   {
00088     for (size_t i = 0; i < cloud->points.size (); ++i)
00089     {
00090       // Get the distance value
00091       const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&cloud->points[i]);
00092       memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float));
00093 
00094       if (limit_negative)
00095       {
00096         // Use a threshold for cutting out points which inside the interval
00097         if ((distance_value < max_distance) && (distance_value > min_distance))
00098           continue;
00099       }
00100       else
00101       {
00102         // Use a threshold for cutting out points which are too close/far away
00103         if ((distance_value > max_distance) || (distance_value < min_distance))
00104           continue;
00105       }
00106 
00107       // Check if the point is invalid
00108       if (!pcl_isfinite (cloud->points[i].x) || 
00109           !pcl_isfinite (cloud->points[i].y) || 
00110           !pcl_isfinite (cloud->points[i].z))
00111         continue;
00112       // Create the point structure and get the min/max
00113       pcl::Array4fMapConst pt = cloud->points[i].getArray4fMap ();
00114       min_p = min_p.min (pt);
00115       max_p = max_p.max (pt);
00116     }
00117   }
00118   min_pt = min_p;
00119   max_pt = max_p;
00120 }
00121 
00122 struct cloud_point_index_idx 
00123 {
00124   unsigned int idx;
00125   unsigned int cloud_point_index;
00126 
00127   cloud_point_index_idx (unsigned int idx_, unsigned int cloud_point_index_) : idx (idx_), cloud_point_index (cloud_point_index_) {}
00128   bool operator < (const cloud_point_index_idx &p) const { return (idx < p.idx); }
00129 };
00130 
00132 template <typename PointT> void
00133 pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)
00134 {
00135   // Has the input dataset been set already?
00136   if (!input_)
00137   {
00138     PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ());
00139     output.width = output.height = 0;
00140     output.points.clear ();
00141     return;
00142   }
00143 
00144   // Copy the header (and thus the frame_id) + allocate enough space for points
00145   output.height       = 1;                    // downsampling breaks the organized structure
00146   output.is_dense     = true;                 // we filter out invalid points
00147 
00148   Eigen::Vector4f min_p, max_p;
00149   // Get the minimum and maximum dimensions
00150   if (!filter_field_name_.empty ()) // If we don't want to process the entire cloud...
00151     getMinMax3D<PointT>(input_, filter_field_name_, static_cast<float> (filter_limit_min_), static_cast<float> (filter_limit_max_), min_p, max_p, filter_limit_negative_);
00152   else
00153     getMinMax3D<PointT>(*input_, min_p, max_p);
00154 
00155   // Compute the minimum and maximum bounding box values
00156   min_b_[0] = static_cast<int> (floor (min_p[0] * inverse_leaf_size_[0]));
00157   max_b_[0] = static_cast<int> (floor (max_p[0] * inverse_leaf_size_[0]));
00158   min_b_[1] = static_cast<int> (floor (min_p[1] * inverse_leaf_size_[1]));
00159   max_b_[1] = static_cast<int> (floor (max_p[1] * inverse_leaf_size_[1]));
00160   min_b_[2] = static_cast<int> (floor (min_p[2] * inverse_leaf_size_[2]));
00161   max_b_[2] = static_cast<int> (floor (max_p[2] * inverse_leaf_size_[2]));
00162 
00163   // Compute the number of divisions needed along all axis
00164   div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones ();
00165   div_b_[3] = 0;
00166 
00167   // Set up the division multiplier
00168   divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0);
00169 
00170   int centroid_size = 4;
00171   if (downsample_all_data_)
00172     centroid_size = boost::mpl::size<FieldList>::value;
00173 
00174   // ---[ RGB special case
00175   std::vector<sensor_msgs::PointField> fields;
00176   int rgba_index = -1;
00177   rgba_index = pcl::getFieldIndex (*input_, "rgb", fields);
00178   if (rgba_index == -1)
00179     rgba_index = pcl::getFieldIndex (*input_, "rgba", fields);
00180   if (rgba_index >= 0)
00181   {
00182     rgba_index = fields[rgba_index].offset;
00183     centroid_size += 3;
00184   }
00185 
00186   std::vector<cloud_point_index_idx> index_vector;
00187   index_vector.reserve(input_->points.size());
00188 
00189   // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first...
00190   if (!filter_field_name_.empty ())
00191   {
00192     // Get the distance field index
00193     std::vector<sensor_msgs::PointField> fields;
00194     int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields);
00195     if (distance_idx == -1)
00196       PCL_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.\n", getClassName ().c_str (), distance_idx);
00197 
00198     // First pass: go over all points and insert them into the index_vector vector
00199     // with calculated idx. Points with the same idx value will contribute to the
00200     // same point of resulting CloudPoint
00201     for (unsigned int cp = 0; cp < static_cast<unsigned int> (input_->points.size ()); ++cp)
00202     {
00203       if (!input_->is_dense)
00204         // Check if the point is invalid
00205         if (!pcl_isfinite (input_->points[cp].x) || 
00206             !pcl_isfinite (input_->points[cp].y) || 
00207             !pcl_isfinite (input_->points[cp].z))
00208           continue;
00209 
00210       // Get the distance value
00211       const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&input_->points[cp]);
00212       float distance_value = 0;
00213       memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float));
00214 
00215       if (filter_limit_negative_)
00216       {
00217         // Use a threshold for cutting out points which inside the interval
00218         if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_))
00219           continue;
00220       }
00221       else
00222       {
00223         // Use a threshold for cutting out points which are too close/far away
00224         if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_))
00225           continue;
00226       }
00227       
00228       int ijk0 = static_cast<int> (floor (input_->points[cp].x * inverse_leaf_size_[0]) - min_b_[0]);
00229       int ijk1 = static_cast<int> (floor (input_->points[cp].y * inverse_leaf_size_[1]) - min_b_[1]);
00230       int ijk2 = static_cast<int> (floor (input_->points[cp].z * inverse_leaf_size_[2]) - min_b_[2]);
00231 
00232       // Compute the centroid leaf index
00233       int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
00234       index_vector.push_back (cloud_point_index_idx (static_cast<unsigned int> (idx), cp));
00235     }
00236   }
00237   // No distance filtering, process all data
00238   else
00239   {
00240     // First pass: go over all points and insert them into the index_vector vector
00241     // with calculated idx. Points with the same idx value will contribute to the
00242     // same point of resulting CloudPoint
00243     for (unsigned int cp = 0; cp < static_cast<unsigned int> (input_->points.size ()); ++cp)
00244     {
00245       if (!input_->is_dense)
00246         // Check if the point is invalid
00247         if (!pcl_isfinite (input_->points[cp].x) || 
00248             !pcl_isfinite (input_->points[cp].y) || 
00249             !pcl_isfinite (input_->points[cp].z))
00250           continue;
00251 
00252       int ijk0 = static_cast<int> (floor (input_->points[cp].x * inverse_leaf_size_[0]) - min_b_[0]);
00253       int ijk1 = static_cast<int> (floor (input_->points[cp].y * inverse_leaf_size_[1]) - min_b_[1]);
00254       int ijk2 = static_cast<int> (floor (input_->points[cp].z * inverse_leaf_size_[2]) - min_b_[2]);
00255 
00256       // Compute the centroid leaf index
00257       int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
00258       index_vector.push_back (cloud_point_index_idx (static_cast<unsigned int> (idx), cp));
00259     }
00260   }
00261 
00262   // Second pass: sort the index_vector vector using value representing target cell as index
00263   // in effect all points belonging to the same output cell will be next to each other
00264   std::sort (index_vector.begin (), index_vector.end (), std::less<cloud_point_index_idx> ());
00265 
00266   // Third pass: count output cells
00267   // we need to skip all the same, adjacenent idx values
00268   unsigned int total = 0;
00269   unsigned int index = 0;
00270   while (index < index_vector.size ()) 
00271   {
00272     unsigned int i = index + 1;
00273     while (i < index_vector.size () && index_vector[i].idx == index_vector[index].idx) 
00274       ++i;
00275     ++total;
00276     index = i;
00277   }
00278 
00279   // Fourth pass: compute centroids, insert them into their final position
00280   output.points.resize (total);
00281   if (save_leaf_layout_)
00282   {
00283     try
00284     { 
00285       // Resizing won't reset old elements to -1.  If leaf_layout_ has been used previously, it needs to be re-initialized to -1
00286       uint32_t new_layout_size = div_b_[0]*div_b_[1]*div_b_[2];
00287       //This is the number of elements that need to be re-initialized to -1
00288       uint32_t reinit_size = std::min (static_cast<unsigned int> (new_layout_size), static_cast<unsigned int> (leaf_layout_.size()));
00289       for (uint32_t i = 0; i < reinit_size; i++)
00290       {
00291         leaf_layout_[i] = -1;
00292       }        
00293       leaf_layout_.resize (new_layout_size, -1);           
00294     }
00295     catch (std::bad_alloc&)
00296     {
00297       throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", 
00298         "voxel_grid.hpp", "applyFilter");       
00299     }
00300     catch (std::length_error&)
00301     {
00302       throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", 
00303         "voxel_grid.hpp", "applyFilter");       
00304     }
00305   }
00306   
00307   index = 0;
00308   Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size);
00309   Eigen::VectorXf temporary = Eigen::VectorXf::Zero (centroid_size);
00310 
00311   for (unsigned int cp = 0; cp < index_vector.size ();)
00312   {
00313     // calculate centroid - sum values from all input points, that have the same idx value in index_vector array
00314     if (!downsample_all_data_) 
00315     {
00316       centroid[0] = input_->points[index_vector[cp].cloud_point_index].x;
00317       centroid[1] = input_->points[index_vector[cp].cloud_point_index].y;
00318       centroid[2] = input_->points[index_vector[cp].cloud_point_index].z;
00319     }
00320     else 
00321     {
00322       // ---[ RGB special case
00323       if (rgba_index >= 0)
00324       {
00325         // Fill r/g/b data, assuming that the order is BGRA
00326         pcl::RGB rgb;
00327         memcpy (&rgb, reinterpret_cast<const char*> (&input_->points[index_vector[cp].cloud_point_index]) + rgba_index, sizeof (RGB));
00328         centroid[centroid_size-3] = rgb.r;
00329         centroid[centroid_size-2] = rgb.g;
00330         centroid[centroid_size-1] = rgb.b;
00331       }
00332       pcl::for_each_type <FieldList> (NdCopyPointEigenFunctor <PointT> (input_->points[index_vector[cp].cloud_point_index], centroid));
00333     }
00334 
00335     unsigned int i = cp + 1;
00336     while (i < index_vector.size () && index_vector[i].idx == index_vector[cp].idx) 
00337     {
00338       if (!downsample_all_data_) 
00339       {
00340         centroid[0] += input_->points[index_vector[i].cloud_point_index].x;
00341         centroid[1] += input_->points[index_vector[i].cloud_point_index].y;
00342         centroid[2] += input_->points[index_vector[i].cloud_point_index].z;
00343       }
00344       else 
00345       {
00346         // ---[ RGB special case
00347         if (rgba_index >= 0)
00348         {
00349           // Fill r/g/b data, assuming that the order is BGRA
00350           pcl::RGB rgb;
00351           memcpy (&rgb, reinterpret_cast<const char*> (&input_->points[index_vector[i].cloud_point_index]) + rgba_index, sizeof (RGB));
00352           temporary[centroid_size-3] = rgb.r;
00353           temporary[centroid_size-2] = rgb.g;
00354           temporary[centroid_size-1] = rgb.b;
00355         }
00356         pcl::for_each_type <FieldList> (NdCopyPointEigenFunctor <PointT> (input_->points[index_vector[i].cloud_point_index], temporary));
00357         centroid += temporary;
00358       }
00359       ++i;
00360     }
00361 
00362     // index is centroid final position in resulting PointCloud
00363     if (save_leaf_layout_)
00364       leaf_layout_[index_vector[cp].idx] = index;
00365 
00366     centroid /= static_cast<float> (i - cp);
00367 
00368     // store centroid
00369     // Do we need to process all the fields?
00370     if (!downsample_all_data_) 
00371     {
00372       output.points[index].x = centroid[0];
00373       output.points[index].y = centroid[1];
00374       output.points[index].z = centroid[2];
00375     }
00376     else 
00377     {
00378       pcl::for_each_type<FieldList> (pcl::NdCopyEigenPointFunctor <PointT> (centroid, output.points[index]));
00379       // ---[ RGB special case
00380       if (rgba_index >= 0) 
00381       {
00382         // pack r/g/b into rgb
00383         float r = centroid[centroid_size-3], g = centroid[centroid_size-2], b = centroid[centroid_size-1];
00384         int rgb = (static_cast<int> (r) << 16) | (static_cast<int> (g) << 8) | static_cast<int> (b);
00385         memcpy (reinterpret_cast<char*> (&output.points[index]) + rgba_index, &rgb, sizeof (float));
00386       }
00387     }
00388     cp = i;
00389     ++index;
00390   }
00391   output.width = static_cast<uint32_t> (output.points.size ());
00392 }
00393 
00394 #define PCL_INSTANTIATE_VoxelGrid(T) template class PCL_EXPORTS pcl::VoxelGrid<T>;
00395 #define PCL_INSTANTIATE_getMinMax3D(T) template PCL_EXPORTS void pcl::getMinMax3D<T> (const pcl::PointCloud<T>::ConstPtr &, const std::string &, float, float, Eigen::Vector4f &, Eigen::Vector4f &, bool);
00396 
00397 #endif    // PCL_FILTERS_IMPL_VOXEL_GRID_H_
00398 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:11