approximate_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 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: voxel_grid.hpp 1600 2011-07-07 16:55:51Z shapovalov $
00035  *
00036  */
00037 
00038 #ifndef PCL_FILTERS_IMPL_FAST_VOXEL_GRID_H_
00039 #define PCL_FILTERS_IMPL_FAST_VOXEL_GRID_H_
00040 
00041 #include <pcl/common/common.h>
00042 #include <pcl/common/io.h>
00043 #include <pcl/filters/approximate_voxel_grid.h>
00044 
00046 template <typename PointT> void
00047 pcl::ApproximateVoxelGrid<PointT>::flush (PointCloud &output, size_t op, he *hhe, int rgba_index, int centroid_size)
00048 {
00049   hhe->centroid /= static_cast<float> (hhe->count);
00050   pcl::for_each_type <FieldList> (pcl::xNdCopyEigenPointFunctor <PointT> (hhe->centroid, output.points[op]));
00051   // ---[ RGB special case
00052   if (rgba_index >= 0)
00053   {
00054     // pack r/g/b into rgb
00055     float r = hhe->centroid[centroid_size-3], 
00056           g = hhe->centroid[centroid_size-2], 
00057           b = hhe->centroid[centroid_size-1];
00058     int rgb = (static_cast<int> (r)) << 16 | (static_cast<int> (g)) << 8 | (static_cast<int> (b));
00059     memcpy (reinterpret_cast<char*> (&output.points[op]) + rgba_index, &rgb, sizeof (float));
00060   }
00061 }
00062 
00064 template <typename PointT> void
00065 pcl::ApproximateVoxelGrid<PointT>::applyFilter (PointCloud &output)
00066 {
00067   int centroid_size = 4;
00068   if (downsample_all_data_)
00069     centroid_size = boost::mpl::size<FieldList>::value;
00070 
00071   // ---[ RGB special case
00072   std::vector<pcl::PCLPointField> fields;
00073   int rgba_index = -1;
00074   rgba_index = pcl::getFieldIndex (*input_, "rgb", fields);
00075   if (rgba_index == -1)
00076     rgba_index = pcl::getFieldIndex (*input_, "rgba", fields);
00077   if (rgba_index >= 0)
00078   {
00079     rgba_index = fields[rgba_index].offset;
00080     centroid_size += 3;
00081   }
00082 
00083   for (size_t i = 0; i < histsize_; i++) 
00084   {
00085     history_[i].count = 0;
00086     history_[i].centroid = Eigen::VectorXf::Zero (centroid_size);
00087   }
00088   Eigen::VectorXf scratch = Eigen::VectorXf::Zero (centroid_size);
00089 
00090   output.points.resize (input_->points.size ());   // size output for worst case
00091   size_t op = 0;    // output pointer
00092   for (size_t cp = 0; cp < input_->points.size (); ++cp) 
00093   {
00094     int ix = static_cast<int> (floor (input_->points[cp].x * inverse_leaf_size_[0]));
00095     int iy = static_cast<int> (floor (input_->points[cp].y * inverse_leaf_size_[1]));
00096     int iz = static_cast<int> (floor (input_->points[cp].z * inverse_leaf_size_[2]));
00097     unsigned int hash = static_cast<unsigned int> ((ix * 7171 + iy * 3079 + iz * 4231) & (histsize_ - 1));
00098     he *hhe = &history_[hash];
00099     if (hhe->count && ((ix != hhe->ix) || (iy != hhe->iy) || (iz != hhe->iz))) 
00100     {
00101       flush (output, op++, hhe, rgba_index, centroid_size);
00102       hhe->count = 0;
00103       hhe->centroid.setZero ();// = Eigen::VectorXf::Zero (centroid_size);
00104     }
00105     hhe->ix = ix;
00106     hhe->iy = iy;
00107     hhe->iz = iz;
00108     hhe->count++;
00109 
00110     // Unpack the point into scratch, then accumulate
00111     // ---[ RGB special case
00112     if (rgba_index >= 0)
00113     {
00114       // fill r/g/b data
00115       pcl::RGB rgb;
00116       memcpy (&rgb, (reinterpret_cast<const char *> (&input_->points[cp])) + rgba_index, sizeof (RGB));
00117       scratch[centroid_size-3] = rgb.r;
00118       scratch[centroid_size-2] = rgb.g;
00119       scratch[centroid_size-1] = rgb.b;
00120     }
00121     pcl::for_each_type <FieldList> (xNdCopyPointEigenFunctor <PointT> (input_->points[cp], scratch));
00122     hhe->centroid += scratch;
00123   }
00124   for (size_t i = 0; i < histsize_; i++) 
00125   {
00126     he *hhe = &history_[i];
00127     if (hhe->count)
00128       flush (output, op++, hhe, rgba_index, centroid_size);
00129   }
00130   output.points.resize (op);
00131   output.width = static_cast<uint32_t> (output.points.size ());
00132   output.height       = 1;                    // downsampling breaks the organized structure
00133   output.is_dense     = false;                 // we filter out invalid points
00134 }
00135 
00136 #define PCL_INSTANTIATE_ApproximateVoxelGrid(T) template class PCL_EXPORTS pcl::ApproximateVoxelGrid<T>;
00137 
00138 #endif    // PCL_FILTERS_IMPL_FAST_VOXEL_GRID_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:35