voxel_grid_label.cpp
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-2011, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  */
00038 
00039 #include <map>
00040 #include <pcl/common/io.h>
00041 #include <pcl/filters/voxel_grid_label.h>
00042 #include <pcl/filters/impl/voxel_grid.hpp>
00043 
00045 void
00046 pcl::VoxelGridLabel::applyFilter (PointCloud &output)
00047 {
00048   // Has the input dataset been set already?
00049   if (!input_)
00050   {
00051     PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ());
00052     output.width = output.height = 0;
00053     output.points.clear ();
00054     return;
00055   }
00056 
00057   // Copy the header (and thus the frame_id) + allocate enough space for points
00058   output.height       = 1;                    // downsampling breaks the organized structure
00059   output.is_dense     = true;                 // we filter out invalid points
00060 
00061   Eigen::Vector4f min_p, max_p;
00062   // Get the minimum and maximum dimensions
00063   if (!filter_field_name_.empty ()) // If we don't want to process the entire cloud...
00064     getMinMax3D<pcl::PointXYZRGBL>(input_, filter_field_name_, static_cast<float> (filter_limit_min_), static_cast<float> (filter_limit_max_), min_p, max_p, filter_limit_negative_);
00065   else
00066     getMinMax3D<pcl::PointXYZRGBL>(*input_, min_p, max_p);
00067 
00068   // Check that the leaf size is not too small, given the size of the data
00069   int64_t dx = static_cast<int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1;
00070   int64_t dy = static_cast<int64_t>((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1;
00071   int64_t dz = static_cast<int64_t>((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1;
00072 
00073   if( (dx*dy*dz) > static_cast<int64_t>(std::numeric_limits<int32_t>::max()) )
00074   {
00075     PCL_WARN("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.", getClassName().c_str());
00076     output.clear();
00077     return;
00078   }
00079 
00080   // Compute the minimum and maximum bounding box values
00081   min_b_[0] = static_cast<int> (floor (min_p[0] * inverse_leaf_size_[0]));
00082   max_b_[0] = static_cast<int> (floor (max_p[0] * inverse_leaf_size_[0]));
00083   min_b_[1] = static_cast<int> (floor (min_p[1] * inverse_leaf_size_[1]));
00084   max_b_[1] = static_cast<int> (floor (max_p[1] * inverse_leaf_size_[1]));
00085   min_b_[2] = static_cast<int> (floor (min_p[2] * inverse_leaf_size_[2]));
00086   max_b_[2] = static_cast<int> (floor (max_p[2] * inverse_leaf_size_[2]));
00087 
00088   // Compute the number of divisions needed along all axis
00089   div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones ();
00090   div_b_[3] = 0;
00091 
00092   // Set up the division multiplier
00093   divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0);
00094 
00095   int centroid_size = 4;
00096   if (downsample_all_data_)
00097     centroid_size = boost::mpl::size<FieldList>::value;
00098 
00099   // ---[ RGB special case
00100   std::vector<pcl::PCLPointField> fields;
00101   int rgba_index = -1;
00102   rgba_index = pcl::getFieldIndex (*input_, "rgb", fields);
00103   if (rgba_index == -1)
00104     rgba_index = pcl::getFieldIndex (*input_, "rgba", fields);
00105   if (rgba_index >= 0)
00106   {
00107     rgba_index = fields[rgba_index].offset;
00108     centroid_size += 3;
00109   }
00110 
00111   // ---[ Label special case
00112   int label_index = -1;
00113   label_index = pcl::getFieldIndex (*input_, "label", fields);
00114 
00115   std::vector<cloud_point_index_idx> index_vector;
00116   index_vector.reserve(input_->points.size());
00117 
00118   // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first...
00119   if (!filter_field_name_.empty ())
00120   {
00121     // Get the distance field index
00122     std::vector<pcl::PCLPointField> fields;
00123     int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields);
00124     if (distance_idx == -1)
00125       PCL_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.\n", getClassName ().c_str (), distance_idx);
00126 
00127     // First pass: go over all points and insert them into the index_vector vector
00128     // with calculated idx. Points with the same idx value will contribute to the
00129     // same point of resulting CloudPoint
00130     for (unsigned int cp = 0; cp < static_cast<unsigned int> (input_->points.size ()); ++cp)
00131     {
00132       if (!input_->is_dense)
00133         // Check if the point is invalid
00134         if (!pcl_isfinite (input_->points[cp].x) || 
00135             !pcl_isfinite (input_->points[cp].y) || 
00136             !pcl_isfinite (input_->points[cp].z))
00137           continue;
00138 
00139       // Get the distance value
00140       const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&input_->points[cp]);
00141       float distance_value = 0;
00142       memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float));
00143 
00144       if (filter_limit_negative_)
00145       {
00146         // Use a threshold for cutting out points which inside the interval
00147         if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_))
00148           continue;
00149       }
00150       else
00151       {
00152         // Use a threshold for cutting out points which are too close/far away
00153         if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_))
00154           continue;
00155       }
00156       
00157       int ijk0 = static_cast<int> (floor (input_->points[cp].x * inverse_leaf_size_[0]) - min_b_[0]);
00158       int ijk1 = static_cast<int> (floor (input_->points[cp].y * inverse_leaf_size_[1]) - min_b_[1]);
00159       int ijk2 = static_cast<int> (floor (input_->points[cp].z * inverse_leaf_size_[2]) - min_b_[2]);
00160 
00161       // Compute the centroid leaf index
00162       int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
00163       index_vector.push_back (cloud_point_index_idx (static_cast<unsigned int> (idx), cp));
00164     }
00165   }
00166   // No distance filtering, process all data
00167   else
00168   {
00169     // First pass: go over all points and insert them into the index_vector vector
00170     // with calculated idx. Points with the same idx value will contribute to the
00171     // same point of resulting CloudPoint
00172     for (unsigned int cp = 0; cp < static_cast<unsigned int> (input_->points.size ()); ++cp)
00173     {
00174       if (!input_->is_dense)
00175         // Check if the point is invalid
00176         if (!pcl_isfinite (input_->points[cp].x) || 
00177             !pcl_isfinite (input_->points[cp].y) || 
00178             !pcl_isfinite (input_->points[cp].z))
00179           continue;
00180 
00181       int ijk0 = static_cast<int> (floor (input_->points[cp].x * inverse_leaf_size_[0]) - min_b_[0]);
00182       int ijk1 = static_cast<int> (floor (input_->points[cp].y * inverse_leaf_size_[1]) - min_b_[1]);
00183       int ijk2 = static_cast<int> (floor (input_->points[cp].z * inverse_leaf_size_[2]) - min_b_[2]);
00184 
00185       // Compute the centroid leaf index
00186       int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
00187       index_vector.push_back (cloud_point_index_idx (static_cast<unsigned int> (idx), cp));
00188     }
00189   }
00190 
00191   // Second pass: sort the index_vector vector using value representing target cell as index
00192   // in effect all points belonging to the same output cell will be next to each other
00193   std::sort (index_vector.begin (), index_vector.end (), std::less<cloud_point_index_idx> ());
00194 
00195   // Third pass: count output cells
00196   // we need to skip all the same, adjacenent idx values
00197   unsigned int total = 0;
00198   unsigned int index = 0;
00199   while (index < index_vector.size ()) 
00200   {
00201     unsigned int i = index + 1;
00202     while (i < index_vector.size () && index_vector[i].idx == index_vector[index].idx) 
00203       ++i;
00204     ++total;
00205     index = i;
00206   }
00207 
00208   // Fourth pass: compute centroids, insert them into their final position
00209   output.points.resize (total);
00210   if (save_leaf_layout_)
00211   {
00212     try
00213     { 
00214       // Resizing won't reset old elements to -1.  If leaf_layout_ has been used previously, it needs to be re-initialized to -1
00215       uint32_t new_layout_size = div_b_[0]*div_b_[1]*div_b_[2];
00216       //This is the number of elements that need to be re-initialized to -1
00217       uint32_t reinit_size = std::min (static_cast<unsigned int> (new_layout_size), static_cast<unsigned int> (leaf_layout_.size()));
00218       for (uint32_t i = 0; i < reinit_size; i++)
00219       {
00220         leaf_layout_[i] = -1;
00221       }        
00222       leaf_layout_.resize (new_layout_size, -1);           
00223     }
00224     catch (std::bad_alloc&)
00225     {
00226       throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", 
00227         "voxel_grid.hpp", "applyFilter");       
00228     }
00229     catch (std::length_error&)
00230     {
00231       throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", 
00232         "voxel_grid.hpp", "applyFilter");       
00233     }
00234   }
00235   
00236   index = 0;
00237   Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size);
00238   Eigen::VectorXf temporary = Eigen::VectorXf::Zero (centroid_size);
00239 
00240   for (unsigned int cp = 0; cp < index_vector.size ();)
00241   {
00242     std::map<int, int> labels;
00243     
00244     // calculate centroid - sum values from all input points, that have the same idx value in index_vector array
00245     if (!downsample_all_data_) 
00246     {
00247       centroid[0] = input_->points[index_vector[cp].cloud_point_index].x;
00248       centroid[1] = input_->points[index_vector[cp].cloud_point_index].y;
00249       centroid[2] = input_->points[index_vector[cp].cloud_point_index].z;
00250     }
00251     else 
00252     {
00253       // ---[ RGB special case
00254       if (rgba_index >= 0)
00255       {
00256         // Fill r/g/b data, assuming that the order is BGRA
00257         pcl::RGB rgb;
00258         memcpy (&rgb, reinterpret_cast<const char*> (&input_->points[index_vector[cp].cloud_point_index]) + rgba_index, sizeof (RGB));
00259         centroid[centroid_size-3] = rgb.r;
00260         centroid[centroid_size-2] = rgb.g;
00261         centroid[centroid_size-1] = rgb.b;
00262       }
00263 
00264       // ---[ Label special case
00265       if (label_index >= 0)
00266       {
00267         // store the label in a map data structure
00268         uint32_t label = input_->points[index_vector[cp].cloud_point_index].label;
00269         std::map<int, int>::iterator it = labels.find (label);
00270         if (it == labels.end ())
00271           labels.insert (labels.begin (), std::pair<int, int> (label, 1));
00272         else
00273           it->second = it->second++;
00274       }
00275 
00276       pcl::for_each_type <FieldList> (NdCopyPointEigenFunctor <pcl::PointXYZRGBL> (input_->points[index_vector[cp].cloud_point_index], centroid));
00277     }
00278 
00279     unsigned int i = cp + 1;
00280     while (i < index_vector.size () && index_vector[i].idx == index_vector[cp].idx) 
00281     {
00282       if (!downsample_all_data_) 
00283       {
00284         centroid[0] += input_->points[index_vector[i].cloud_point_index].x;
00285         centroid[1] += input_->points[index_vector[i].cloud_point_index].y;
00286         centroid[2] += input_->points[index_vector[i].cloud_point_index].z;
00287       }
00288       else 
00289       {
00290         // ---[ RGB special case
00291         if (rgba_index >= 0)
00292         {
00293           // Fill r/g/b data, assuming that the order is BGRA
00294           pcl::RGB rgb;
00295           memcpy (&rgb, reinterpret_cast<const char*> (&input_->points[index_vector[i].cloud_point_index]) + rgba_index, sizeof (RGB));
00296           temporary[centroid_size-3] = rgb.r;
00297           temporary[centroid_size-2] = rgb.g;
00298           temporary[centroid_size-1] = rgb.b;
00299         }
00300         pcl::for_each_type <FieldList> (NdCopyPointEigenFunctor <pcl::PointXYZRGBL> (input_->points[index_vector[i].cloud_point_index], temporary));
00301         centroid += temporary;
00302       }
00303       ++i;
00304     }
00305 
00306     // index is centroid final position in resulting PointCloud
00307     if (save_leaf_layout_)
00308       leaf_layout_[index_vector[cp].idx] = index;
00309 
00310     centroid /= static_cast<float> (i - cp);
00311 
00312     // store centroid
00313     // Do we need to process all the fields?
00314     if (!downsample_all_data_) 
00315     {
00316       output.points[index].x = centroid[0];
00317       output.points[index].y = centroid[1];
00318       output.points[index].z = centroid[2];
00319     }
00320     else 
00321     {
00322       pcl::for_each_type<FieldList> (pcl::NdCopyEigenPointFunctor <pcl::PointXYZRGBL> (centroid, output.points[index]));
00323       // ---[ RGB special case
00324       if (rgba_index >= 0) 
00325       {
00326         // pack r/g/b into rgb
00327         float r = centroid[centroid_size-3], g = centroid[centroid_size-2], b = centroid[centroid_size-1];
00328         int rgb = (static_cast<int> (r) << 16) | (static_cast<int> (g) << 8) | static_cast<int> (b);
00329         memcpy (reinterpret_cast<char*> (&output.points[index]) + rgba_index, &rgb, sizeof (float));
00330       }
00331 
00332       if (label_index >= 0)
00333       {
00334         // find the label with the highest occurrence
00335         std::map<int, int>::iterator it = labels.begin ();
00336         int n_occurrence = it->second;
00337         int label = it->first;
00338         if (it != labels.end ())
00339         {
00340           for (it = labels.begin (); it != labels.end (); it++)
00341           {
00342             if (n_occurrence < it->second)
00343             {
00344               n_occurrence = it->second;
00345               label = it->first;
00346             }
00347           }
00348         }
00349         output.points[index].label = label;
00350       }
00351     }
00352     cp = i;
00353     ++index;
00354   }
00355   output.width = static_cast<uint32_t> (output.points.size ());
00356 }
00357 


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