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 #include "pcl/impl/instantiate.hpp"
00039 #include "pcl/point_types.h"
00040 #include "pcl/io/io.h"
00041 #include "pcl/filters/voxel_grid.h"
00042 #include "pcl/filters/impl/voxel_grid.hpp"
00043
00045 void
00046 pcl::getMinMax3D (const sensor_msgs::PointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
00047 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt)
00048 {
00049
00050 if (cloud->fields[x_idx].datatype != sensor_msgs::PointField::FLOAT32 ||
00051 cloud->fields[y_idx].datatype != sensor_msgs::PointField::FLOAT32 ||
00052 cloud->fields[z_idx].datatype != sensor_msgs::PointField::FLOAT32)
00053 {
00054 ROS_ERROR ("[pcl::getMinMax3D] XYZ dimensions are not float type!");
00055 return;
00056 }
00057
00058 Eigen::Array4f min_p, max_p;
00059 min_p.setConstant (FLT_MAX);
00060 max_p.setConstant (-FLT_MAX);
00061
00062 int nr_points = cloud->width * cloud->height;
00063
00064 Eigen::Array4f pt = Eigen::Array4f::Zero ();
00065 Eigen::Array4i xyz_offset (cloud->fields[x_idx].offset, cloud->fields[y_idx].offset, cloud->fields[z_idx].offset, 0);
00066
00067 for (int cp = 0; cp < nr_points; ++cp)
00068 {
00069
00070 memcpy (&pt[0], &cloud->data[xyz_offset[0]], sizeof (float));
00071 memcpy (&pt[1], &cloud->data[xyz_offset[1]], sizeof (float));
00072 memcpy (&pt[2], &cloud->data[xyz_offset[2]], sizeof (float));
00073
00074 if (!pcl_isfinite (pt[0]) ||
00075 !pcl_isfinite (pt[1]) ||
00076 !pcl_isfinite (pt[2]))
00077 {
00078 xyz_offset += cloud->point_step;
00079 continue;
00080 }
00081 xyz_offset += cloud->point_step;
00082 min_p = (min_p.min) (pt);
00083 max_p = (max_p.max) (pt);
00084 }
00085 min_pt = min_p;
00086 max_pt = max_p;
00087 }
00088
00090 void
00091 pcl::getMinMax3D (const sensor_msgs::PointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
00092 const std::string &distance_field_name, float min_distance, float max_distance,
00093 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative)
00094 {
00095
00096 if (cloud->fields[x_idx].datatype != sensor_msgs::PointField::FLOAT32 ||
00097 cloud->fields[y_idx].datatype != sensor_msgs::PointField::FLOAT32 ||
00098 cloud->fields[z_idx].datatype != sensor_msgs::PointField::FLOAT32)
00099 {
00100 ROS_ERROR ("[pcl::getMinMax3D] XYZ dimensions are not float type!");
00101 return;
00102 }
00103
00104 Eigen::Array4f min_p, max_p;
00105 min_p.setConstant (FLT_MAX);
00106 max_p.setConstant (-FLT_MAX);
00107
00108
00109 int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name);
00110
00111
00112 if (cloud->fields[distance_idx].datatype != sensor_msgs::PointField::FLOAT32)
00113 {
00114 ROS_ERROR ("[pcl::getMinMax3D] Filtering dimensions is not float type!");
00115 return;
00116 }
00117
00118 int nr_points = cloud->width * cloud->height;
00119
00120 Eigen::Array4f pt = Eigen::Array4f::Zero ();
00121 Eigen::Array4i xyz_offset (cloud->fields[x_idx].offset,
00122 cloud->fields[y_idx].offset,
00123 cloud->fields[z_idx].offset,
00124 0);
00125 float distance_value = 0;
00126 for (int cp = 0; cp < nr_points; ++cp)
00127 {
00128 int point_offset = cp * cloud->point_step;
00129
00130
00131 memcpy (&distance_value, &cloud->data[point_offset + cloud->fields[distance_idx].offset], sizeof (float));
00132
00133 if (limit_negative)
00134 {
00135
00136 if ((distance_value < max_distance) && (distance_value > min_distance))
00137 {
00138 xyz_offset += cloud->point_step;
00139 continue;
00140 }
00141 }
00142 else
00143 {
00144
00145 if ((distance_value > max_distance) || (distance_value < min_distance))
00146 {
00147 xyz_offset += cloud->point_step;
00148 continue;
00149 }
00150 }
00151
00152
00153 memcpy (&pt[0], &cloud->data[xyz_offset[0]], sizeof (float));
00154 memcpy (&pt[1], &cloud->data[xyz_offset[1]], sizeof (float));
00155 memcpy (&pt[2], &cloud->data[xyz_offset[2]], sizeof (float));
00156
00157 if (!pcl_isfinite (pt[0]) ||
00158 !pcl_isfinite (pt[1]) ||
00159 !pcl_isfinite (pt[2]))
00160 {
00161 xyz_offset += cloud->point_step;
00162 continue;
00163 }
00164 xyz_offset += cloud->point_step;
00165 min_p = (min_p.min) (pt);
00166 max_p = (max_p.max) (pt);
00167 }
00168 min_pt = min_p;
00169 max_pt = max_p;
00170 }
00171
00173 void
00174 pcl::VoxelGrid<sensor_msgs::PointCloud2>::applyFilter (PointCloud2 &output)
00175 {
00176
00177 if (x_idx_ == -1 || y_idx_ == -1 || z_idx_ == -1)
00178 {
00179 ROS_ERROR ("[pcl::%s::applyFilter] Input dataset doesn't have x-y-z coordinates!", getClassName ().c_str ());
00180 output.width = output.height = 0;
00181 output.data.clear ();
00182 return;
00183 }
00184
00185 if (leaf_size_[3] == 0)
00186 leaf_size_[3] = 1;
00187
00188 int nr_points = input_->width * input_->height;
00189
00190
00191 output.height = 1;
00192 if (downsample_all_data_)
00193 {
00194 output.fields = input_->fields;
00195 output.point_step = input_->point_step;
00196 }
00197 else
00198 {
00199 output.fields.resize (4);
00200
00201 output.fields[0] = input_->fields[x_idx_];
00202 output.fields[0].offset = 0;
00203
00204 output.fields[1] = input_->fields[y_idx_];
00205 output.fields[1].offset = 4;
00206
00207 output.fields[2] = input_->fields[z_idx_];
00208 output.fields[2].offset = 8;
00209
00210 output.fields[3].name = "rgba";
00211 output.fields[3].offset = 12;
00212 output.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
00213
00214 output.point_step = 16;
00215 }
00216 output.is_bigendian = input_->is_bigendian;
00217 output.row_step = input_->row_step;
00218 output.is_dense = true;
00219
00220 Eigen::Vector4f min_p, max_p;
00221
00222 if (!filter_field_name_.empty ())
00223 getMinMax3D (input_, x_idx_, y_idx_, z_idx_, filter_field_name_, filter_limit_min_, filter_limit_max_, min_p, max_p, filter_limit_negative_);
00224 else
00225 getMinMax3D (input_, x_idx_, y_idx_, z_idx_, min_p, max_p);
00226
00227
00228 Eigen::Array4f inverse_leaf_size = Eigen::Array4f::Ones () / leaf_size_.array ();
00229
00230
00231
00232
00233
00234 min_b_[0] = (int)(floor (min_p[0] * inverse_leaf_size[0]));
00235 max_b_[0] = (int)(floor (max_p[0] * inverse_leaf_size[0]));
00236 min_b_[1] = (int)(floor (min_p[1] * inverse_leaf_size[1]));
00237 max_b_[1] = (int)(floor (max_p[1] * inverse_leaf_size[1]));
00238 min_b_[2] = (int)(floor (min_p[2] * inverse_leaf_size[2]));
00239 max_b_[2] = (int)(floor (max_p[2] * inverse_leaf_size[2]));
00240
00241
00242 div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones ();
00243 div_b_[3] = 0;
00244
00245
00246 leaves_.clear();
00247
00248
00249 Eigen::Array4i xyz_offset (input_->fields[x_idx_].offset,
00250 input_->fields[y_idx_].offset,
00251 input_->fields[z_idx_].offset,
00252 0);
00253 divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0);
00254 Eigen::Vector4f pt = Eigen::Vector4f::Zero ();
00255 Eigen::Vector4i ijk = Eigen::Vector4i::Zero ();
00256
00257 int centroid_size = 4;
00258 if (downsample_all_data_)
00259 centroid_size = input_->fields.size ();
00260
00261 int rgba_index = -1;
00262
00263
00264
00265 for (int d = 0; d < centroid_size; ++d)
00266 {
00267 if (input_->fields[d].name == std::string("rgba") || input_->fields[d].name == std::string("rgb"))
00268 {
00269 rgba_index = d;
00270 centroid_size += 3;
00271 break;
00272 }
00273 }
00274
00275
00276 if (!filter_field_name_.empty ())
00277 {
00278
00279 int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_);
00280
00281
00282 if (input_->fields[distance_idx].datatype != sensor_msgs::PointField::FLOAT32)
00283 {
00284 ROS_ERROR ("[pcl::%s::applyFilter] Distance filtering requested, but distances are not float/double in the dataset! Only FLOAT32/FLOAT64 distances are supported right now.", getClassName ().c_str ());
00285 output.width = output.height = 0;
00286 output.data.clear ();
00287 return;
00288 }
00289
00290
00291 float distance_value = 0;
00292 for (int cp = 0; cp < nr_points; ++cp)
00293 {
00294 int point_offset = cp * input_->point_step;
00295
00296 memcpy (&distance_value, &input_->data[point_offset + input_->fields[distance_idx].offset], sizeof (float));
00297
00298 if (filter_limit_negative_)
00299 {
00300
00301 if (distance_value < filter_limit_max_ && distance_value > filter_limit_min_)
00302 {
00303 xyz_offset += input_->point_step;
00304 continue;
00305 }
00306 }
00307 else
00308 {
00309
00310 if (distance_value > filter_limit_max_ || distance_value < filter_limit_min_)
00311 {
00312 xyz_offset += input_->point_step;
00313 continue;
00314 }
00315 }
00316
00317
00318 memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof (float));
00319 memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof (float));
00320 memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof (float));
00321
00322
00323 if (!pcl_isfinite (pt[0]) ||
00324 !pcl_isfinite (pt[1]) ||
00325 !pcl_isfinite (pt[2]))
00326 {
00327 xyz_offset += input_->point_step;
00328 continue;
00329 }
00330
00331
00332
00333 ijk[0] = (int)(floor (pt[0] * inverse_leaf_size[0]));
00334 ijk[1] = (int)(floor (pt[1] * inverse_leaf_size[1]));
00335 ijk[2] = (int)(floor (pt[2] * inverse_leaf_size[2]));
00336
00337
00338 int idx = (ijk - min_b_).dot (divb_mul_);
00339 Leaf& leaf = leaves_[idx];
00340
00341 if (leaf.nr_points == 0)
00342 {
00343 leaf.centroid.resize (centroid_size);
00344 leaf.centroid.setZero ();
00345 }
00346
00347
00348 if (!downsample_all_data_)
00349 {
00350 leaf.centroid.head<4> () += pt;
00351 }
00352 else
00353 {
00354 Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size);
00355
00356
00357 if (rgba_index >= 0)
00358 {
00359 int rgb;
00360 memcpy (&rgb, &input_->data[point_offset + input_->fields[rgba_index].offset], sizeof (int));
00361 centroid[centroid_size-3] = (rgb>>16) & 0x0000ff;
00362 centroid[centroid_size-2] = (rgb>>8) & 0x0000ff;
00363 centroid[centroid_size-1] = (rgb) & 0x0000ff;
00364 }
00365
00366 for (unsigned int d = 0; d < input_->fields.size (); ++d)
00367 memcpy (¢roid[d], &input_->data[point_offset + input_->fields[d].offset], field_sizes_[d]);
00368 leaf.centroid += centroid;
00369 }
00370 ++leaf.nr_points;
00371
00372 xyz_offset += input_->point_step;
00373 }
00374 }
00375
00376 else
00377 {
00378
00379 for (int cp = 0; cp < nr_points; ++cp)
00380 {
00381
00382 memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof (float));
00383 memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof (float));
00384 memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof (float));
00385
00386
00387 if (!pcl_isfinite (pt[0]) ||
00388 !pcl_isfinite (pt[1]) ||
00389 !pcl_isfinite (pt[2]))
00390 {
00391 xyz_offset += input_->point_step;
00392 continue;
00393 }
00394
00395
00396
00397 ijk[0] = (int)(floor (pt[0] * inverse_leaf_size[0]));
00398 ijk[1] = (int)(floor (pt[1] * inverse_leaf_size[1]));
00399 ijk[2] = (int)(floor (pt[2] * inverse_leaf_size[2]));
00400
00401
00402 int idx = (ijk - min_b_).dot (divb_mul_);
00403
00404
00405 Leaf& leaf = leaves_[idx];
00406
00407 if (leaf.nr_points == 0)
00408 {
00409 leaf.centroid.resize (centroid_size);
00410 leaf.centroid.setZero ();
00411 }
00412
00413
00414 if (!downsample_all_data_)
00415 {
00416 leaf.centroid.head<4> () += pt;
00417 }
00418 else
00419 {
00420 Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size);
00421 int point_offset = cp * input_->point_step;
00422
00423
00424 if (rgba_index >= 0)
00425 {
00426 int rgb;
00427 memcpy (&rgb, &input_->data[point_offset + input_->fields[rgba_index].offset], sizeof (int));
00428 centroid[centroid_size-3] = (rgb>>16) & 0x0000ff;
00429 centroid[centroid_size-2] = (rgb>>8) & 0x0000ff;
00430 centroid[centroid_size-1] = (rgb) & 0x0000ff;
00431 }
00432
00433 for (unsigned int d = 0; d < input_->fields.size(); ++d)
00434 memcpy (¢roid[d], &input_->data[point_offset + input_->fields[d].offset], field_sizes_[d]);
00435 leaf.centroid += centroid;
00436 }
00437 ++leaf.nr_points;
00438
00439 xyz_offset += input_->point_step;
00440 }
00441 }
00442
00443
00444 int nr_p = 0;
00445
00446 if (downsample_all_data_)
00447 xyz_offset = Eigen::Array4i (output.fields[x_idx_].offset,
00448 output.fields[y_idx_].offset,
00449 output.fields[z_idx_].offset,
00450 0);
00451 else
00452
00453 xyz_offset = Eigen::Array4i (0, 4, 8, 12);
00454
00455 Eigen::VectorXf centroid;
00456 output.width = leaves_.size ();
00457 output.row_step = output.point_step * output.width;
00458 output.data.resize (output.width * output.point_step);
00459
00460 leaf_layout_.clear ();
00461 if (save_leaf_layout_)
00462 leaf_layout_.resize (div_b_[0]*div_b_[1]*div_b_[2], -1);
00463
00464 int cp = 0;
00465 for (std::map<size_t, Leaf>::const_iterator it = leaves_.begin (); it != leaves_.end (); ++it)
00466 {
00467
00468 if (save_leaf_layout_)
00469 leaf_layout_[it->first] = cp++;
00470
00471
00472 const Leaf& leaf = it->second;
00473 float norm_pts = 1.0f / leaf.nr_points;
00474 centroid = leaf.centroid * norm_pts;
00475
00476
00477 if (!downsample_all_data_)
00478 {
00479
00480 memcpy (&output.data[xyz_offset[0]], ¢roid[0], sizeof (float));
00481 memcpy (&output.data[xyz_offset[1]], ¢roid[1], sizeof (float));
00482 memcpy (&output.data[xyz_offset[2]], ¢roid[2], sizeof (float));
00483 xyz_offset += output.point_step;
00484 }
00485 else
00486 {
00487 int point_offset = nr_p * output.point_step;
00488
00489 for (size_t d = 0; d < output.fields.size (); ++d)
00490 memcpy (&output.data[point_offset + output.fields[d].offset], ¢roid[d], field_sizes_[d]);
00491
00492
00493
00494 if (rgba_index >= 0)
00495 {
00496 float r = centroid[centroid_size-3], g = centroid[centroid_size-2], b = centroid[centroid_size-1];
00497 int rgb = ((int)r) << 16 | ((int)g) << 8 | ((int)b);
00498 memcpy (&output.data[point_offset + output.fields[rgba_index].offset], &rgb, sizeof(float));
00499 }
00500 }
00501 ++nr_p;
00502 }
00503 }
00504
00505
00506 PCL_INSTANTIATE(getMinMax3D, PCL_XYZ_POINT_TYPES);
00507 PCL_INSTANTIATE(VoxelGrid, PCL_XYZ_POINT_TYPES);
00508