Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
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/filters/approximate_voxel_grid.h>
00043
00045 template <typename PointT> void
00046 pcl::ApproximateVoxelGrid<PointT>::flush (PointCloud &output, size_t op, he *hhe, int rgba_index, int centroid_size)
00047 {
00048 hhe->centroid /= static_cast<float> (hhe->count);
00049 pcl::for_each_type <FieldList> (pcl::xNdCopyEigenPointFunctor <PointT> (hhe->centroid, output.points[op]));
00050
00051 if (rgba_index >= 0)
00052 {
00053
00054 float r = hhe->centroid[centroid_size-3],
00055 g = hhe->centroid[centroid_size-2],
00056 b = hhe->centroid[centroid_size-1];
00057 int rgb = (static_cast<int> (r)) << 16 | (static_cast<int> (g)) << 8 | (static_cast<int> (b));
00058 memcpy (reinterpret_cast<char*> (&output.points[op]) + rgba_index, &rgb, sizeof (float));
00059 }
00060 }
00061
00063 template <typename PointT> void
00064 pcl::ApproximateVoxelGrid<PointT>::applyFilter (PointCloud &output)
00065 {
00066 int centroid_size = 4;
00067 if (downsample_all_data_)
00068 centroid_size = boost::mpl::size<FieldList>::value;
00069
00070
00071 std::vector<sensor_msgs::PointField> fields;
00072 int rgba_index = -1;
00073 rgba_index = pcl::getFieldIndex (*input_, "rgb", fields);
00074 if (rgba_index == -1)
00075 rgba_index = pcl::getFieldIndex (*input_, "rgba", fields);
00076 if (rgba_index >= 0)
00077 {
00078 rgba_index = fields[rgba_index].offset;
00079 centroid_size += 3;
00080 }
00081
00082 for (size_t i = 0; i < histsize_; i++)
00083 {
00084 history_[i].count = 0;
00085 history_[i].centroid = Eigen::VectorXf::Zero (centroid_size);
00086 }
00087 Eigen::VectorXf scratch = Eigen::VectorXf::Zero (centroid_size);
00088
00089 output.points.resize (input_->points.size ());
00090 size_t op = 0;
00091 for (size_t cp = 0; cp < input_->points.size (); ++cp)
00092 {
00093 int ix = static_cast<int> (floor (input_->points[cp].x * inverse_leaf_size_[0]));
00094 int iy = static_cast<int> (floor (input_->points[cp].y * inverse_leaf_size_[1]));
00095 int iz = static_cast<int> (floor (input_->points[cp].z * inverse_leaf_size_[2]));
00096 unsigned int hash = static_cast<unsigned int> ((ix * 7171 + iy * 3079 + iz * 4231) & (histsize_ - 1));
00097 he *hhe = &history_[hash];
00098 if (hhe->count && ((ix != hhe->ix) || (iy != hhe->iy) || (iz != hhe->iz)))
00099 {
00100 flush (output, op++, hhe, rgba_index, centroid_size);
00101 hhe->count = 0;
00102 hhe->centroid.setZero ();
00103 }
00104 hhe->ix = ix;
00105 hhe->iy = iy;
00106 hhe->iz = iz;
00107 hhe->count++;
00108
00109
00110
00111 if (rgba_index >= 0)
00112 {
00113
00114 pcl::RGB rgb;
00115 memcpy (&rgb, (reinterpret_cast<const char *> (&input_->points[cp])) + rgba_index, sizeof (RGB));
00116 scratch[centroid_size-3] = rgb.r;
00117 scratch[centroid_size-2] = rgb.g;
00118 scratch[centroid_size-1] = rgb.b;
00119 }
00120 pcl::for_each_type <FieldList> (xNdCopyPointEigenFunctor <PointT> (input_->points[cp], scratch));
00121 hhe->centroid += scratch;
00122 }
00123 for (size_t i = 0; i < histsize_; i++)
00124 {
00125 he *hhe = &history_[i];
00126 if (hhe->count)
00127 flush (output, op++, hhe, rgba_index, centroid_size);
00128 }
00129 output.points.resize (op);
00130 output.width = static_cast<uint32_t> (output.points.size ());
00131 output.height = 1;
00132 output.is_dense = false;
00133 }
00134
00135 #define PCL_INSTANTIATE_ApproximateVoxelGrid(T) template class PCL_EXPORTS pcl::ApproximateVoxelGrid<T>;
00136
00137 #endif // PCL_FILTERS_IMPL_FAST_VOXEL_GRID_H_