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_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
00044 template <typename PointT> void
00045 pcl::getMinMax3D (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
00046 const std::string &distance_field_name, float min_distance, float max_distance,
00047 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative)
00048 {
00049 Eigen::Array4f min_p, max_p;
00050 min_p.setConstant (FLT_MAX);
00051 max_p.setConstant (-FLT_MAX);
00052
00053
00054 std::vector<sensor_msgs::PointField> fields;
00055 int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name, fields);
00056
00057 float distance_value;
00058 for (size_t i = 0; i < cloud->points.size (); ++i)
00059 {
00060
00061 uint8_t* pt_data = (uint8_t*)&cloud->points[i];
00062 memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float));
00063
00064 if (limit_negative)
00065 {
00066
00067 if ((distance_value < max_distance) && (distance_value > min_distance))
00068 continue;
00069 }
00070 else
00071 {
00072
00073 if ((distance_value > max_distance) || (distance_value < min_distance))
00074 continue;
00075 }
00076
00077
00078 if (!pcl_isfinite (cloud->points[i].x) ||
00079 !pcl_isfinite (cloud->points[i].y) ||
00080 !pcl_isfinite (cloud->points[i].z))
00081 continue;
00082
00083 pcl::Array4fMapConst pt = cloud->points[i].getArray4fMap ();
00084 min_p = min_p.min (pt);
00085 max_p = max_p.max (pt);
00086 }
00087 min_pt = min_p;
00088 max_pt = max_p;
00089 }
00090
00092 template <typename PointT> void
00093 pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)
00094 {
00095
00096 if (!input_)
00097 {
00098 ROS_WARN ("[pcl::%s::applyFilter] No input dataset given!", getClassName ().c_str ());
00099 output.width = output.height = 0;
00100 output.points.clear ();
00101 return;
00102 }
00103
00104 if (leaf_size_[3] == 0)
00105 leaf_size_[3] = 1;
00106
00107
00108 output.height = 1;
00109 output.is_dense = true;
00110
00111 Eigen::Vector4f min_p, max_p;
00112
00113 if (!filter_field_name_.empty ())
00114 getMinMax3D<PointT>(input_, filter_field_name_, filter_limit_min_, filter_limit_max_, min_p, max_p, filter_limit_negative_);
00115 else
00116 getMinMax3D<PointT>(*input_, min_p, max_p);
00117
00118
00119 Eigen::Array4f inverse_leaf_size = Eigen::Array4f::Ones () / leaf_size_.array ();
00120
00121
00122
00123
00124
00125 min_b_[0] = (int)(floor (min_p[0] * inverse_leaf_size[0]));
00126 max_b_[0] = (int)(floor (max_p[0] * inverse_leaf_size[0]));
00127 min_b_[1] = (int)(floor (min_p[1] * inverse_leaf_size[1]));
00128 max_b_[1] = (int)(floor (max_p[1] * inverse_leaf_size[1]));
00129 min_b_[2] = (int)(floor (min_p[2] * inverse_leaf_size[2]));
00130 max_b_[2] = (int)(floor (max_p[2] * inverse_leaf_size[2]));
00131
00132
00133 div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones ();
00134 div_b_[3] = 0;
00135
00136
00137 leaves_.clear();
00138
00139
00140 divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0);
00141 Eigen::Vector4i ijk = Eigen::Vector4i::Zero ();
00142
00143 int centroid_size = 4;
00144 if (downsample_all_data_)
00145 centroid_size = boost::mpl::size<FieldList>::value;
00146
00147
00148 std::vector<sensor_msgs::PointField> fields;
00149 int rgba_index = -1;
00150 rgba_index = pcl::getFieldIndex (*input_, "rgb", fields);
00151 if (rgba_index == -1)
00152 {
00153 rgba_index = pcl::getFieldIndex (*input_, "rgba", fields);
00154 }
00155 if (rgba_index >= 0)
00156 {
00157 rgba_index = fields[rgba_index].offset;
00158 centroid_size += 3;
00159 }
00160
00161
00162 if (!filter_field_name_.empty ())
00163 {
00164
00165 std::vector<sensor_msgs::PointField> fields;
00166 int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_, fields);
00167 if (distance_idx == -1)
00168 ROS_WARN ("[pcl::%s::applyFilter] Invalid filter field name. Index is %d.", getClassName ().c_str (), distance_idx);
00169
00170
00171 for (size_t cp = 0; cp < input_->points.size (); ++cp)
00172 {
00173
00174 if (!pcl_isfinite (input_->points[cp].x) ||
00175 !pcl_isfinite (input_->points[cp].y) ||
00176 !pcl_isfinite (input_->points[cp].z))
00177 continue;
00178
00179
00180 uint8_t* pt_data = (uint8_t*)&input_->points[cp];
00181 float distance_value = 0;
00182 memcpy (&distance_value, pt_data + fields[distance_idx].offset, sizeof (float));
00183
00184 if (filter_limit_negative_)
00185 {
00186
00187 if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_))
00188 continue;
00189 }
00190 else
00191 {
00192
00193 if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_))
00194 continue;
00195 }
00196
00197 Eigen::Vector4f pt (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z, 0);
00198
00199
00200
00201 ijk[0] = (int)(floor (pt[0] * inverse_leaf_size[0]));
00202 ijk[1] = (int)(floor (pt[1] * inverse_leaf_size[1]));
00203 ijk[2] = (int)(floor (pt[2] * inverse_leaf_size[2]));
00204
00205
00206 int idx = (ijk - min_b_).dot (divb_mul_);
00207 Leaf& leaf = leaves_[idx];
00208 if (leaf.nr_points == 0)
00209 {
00210 leaf.centroid.resize (centroid_size);
00211 leaf.centroid.setZero ();
00212 }
00213
00214
00215 if (!downsample_all_data_)
00216 {
00217 leaf.centroid.template head<4> () += pt;
00218 }
00219 else
00220 {
00221
00222 Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size);
00223
00224 if (rgba_index >= 0)
00225 {
00226
00227 int rgb;
00228 memcpy (&rgb, ((char *)&(input_->points[cp])) + rgba_index, sizeof (int));
00229 centroid[centroid_size-3] = (rgb>>16) & 0x0000ff;
00230 centroid[centroid_size-2] = (rgb>>8) & 0x0000ff;
00231 centroid[centroid_size-1] = (rgb) & 0x0000ff;
00232 }
00233 pcl::for_each_type <FieldList> (NdCopyPointEigenFunctor <PointT> (input_->points[cp], centroid));
00234 leaf.centroid += centroid;
00235 }
00236 ++leaf.nr_points;
00237 }
00238 }
00239
00240 else
00241 {
00242
00243 for (size_t cp = 0; cp < input_->points.size (); ++cp)
00244 {
00245
00246 if (!pcl_isfinite (input_->points[cp].x) ||
00247 !pcl_isfinite (input_->points[cp].y) ||
00248 !pcl_isfinite (input_->points[cp].z))
00249 continue;
00250
00251 Eigen::Vector4f pt (input_->points[cp].x, input_->points[cp].y, input_->points[cp].z, 0);
00252
00253
00254
00255 ijk[0] = (int)(floor (pt[0] * inverse_leaf_size[0]));
00256 ijk[1] = (int)(floor (pt[1] * inverse_leaf_size[1]));
00257 ijk[2] = (int)(floor (pt[2] * inverse_leaf_size[2]));
00258
00259
00260 int idx = (ijk - min_b_).dot (divb_mul_);
00261 Leaf& leaf = leaves_[idx];
00262 if (leaf.nr_points == 0)
00263 {
00264 leaf.centroid.resize (centroid_size);
00265 leaf.centroid.setZero ();
00266 }
00267
00268
00269 if (!downsample_all_data_)
00270 {
00271 leaf.centroid.template head<4> () += pt;
00272 }
00273 else
00274 {
00275
00276 Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size);
00277
00278 if (rgba_index >= 0)
00279 {
00280
00281 int rgb;
00282 memcpy (&rgb, ((char *)&(input_->points[cp])) + rgba_index, sizeof (int));
00283 centroid[centroid_size-3] = (rgb>>16) & 0x0000ff;
00284 centroid[centroid_size-2] = (rgb>>8) & 0x0000ff;
00285 centroid[centroid_size-1] = (rgb) & 0x0000ff;
00286 }
00287 pcl::for_each_type <FieldList> (NdCopyPointEigenFunctor <PointT> (input_->points[cp], centroid));
00288 leaf.centroid += centroid;
00289 }
00290 ++leaf.nr_points;
00291 }
00292 }
00293
00294
00295 output.points.clear ();
00296 output.points.reserve (leaves_.size ());
00297 int cp = 0;
00298 leaf_layout_.clear ();
00299 if (save_leaf_layout_)
00300 leaf_layout_.resize (div_b_[0]*div_b_[1]*div_b_[2], -1);
00301 for (typename std::map<size_t, Leaf>::const_iterator it = leaves_.begin (); it != leaves_.end (); ++it)
00302 {
00303
00304 if (save_leaf_layout_)
00305 leaf_layout_[it->first] = cp++;
00306
00307
00308 const Leaf& leaf = it->second;
00309 output.points.push_back (PointT ());
00310 PointT& point = output.points.back ();
00311
00312
00313 float norm_pts = 1.0f / leaf.nr_points;
00314 Eigen::VectorXf centroid = leaf.centroid * norm_pts;
00315
00316
00317 if (!downsample_all_data_)
00318 {
00319 point.x = centroid[0];
00320 point.y = centroid[1];
00321 point.z = centroid[2];
00322 }
00323 else
00324 {
00325 pcl::for_each_type <FieldList> (pcl::NdCopyEigenPointFunctor <PointT> (centroid, point));
00326
00327 if (rgba_index >= 0)
00328 {
00329
00330 float r = centroid[centroid_size-3], g = centroid[centroid_size-2], b = centroid[centroid_size-1];
00331 int rgb = ((int)r) << 16 | ((int)g) << 8 | ((int)b);
00332 memcpy (((char *)&point) + rgba_index, &rgb, sizeof (float));
00333 }
00334 }
00335 }
00336 output.width = output.points.size ();
00337 }
00338
00339 #define PCL_INSTANTIATE_VoxelGrid(T) template class pcl::VoxelGrid<T>;
00340 #define PCL_INSTANTIATE_getMinMax3D(T) template void pcl::getMinMax3D<T> (const pcl::PointCloud<T>::ConstPtr &, const std::string &, float, float, Eigen::Vector4f &, Eigen::Vector4f &, bool);
00341
00342 #endif // PCL_FILTERS_IMPL_VOXEL_GRID_H_
00343