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 #include "rtabmap/core/util3d_filtering.h"
00029
00030 #include <pcl/filters/extract_indices.h>
00031 #include <pcl/filters/voxel_grid.h>
00032 #include <pcl/filters/frustum_culling.h>
00033 #include <pcl/filters/random_sample.h>
00034 #include <pcl/filters/passthrough.h>
00035
00036 #include <pcl/features/normal_3d_omp.h>
00037
00038 #include <pcl/search/kdtree.h>
00039
00040 #include <pcl/common/common.h>
00041
00042 #include <pcl/segmentation/extract_clusters.h>
00043 #include <pcl/segmentation/sac_segmentation.h>
00044
00045 #include <rtabmap/utilite/ULogger.h>
00046 #include <rtabmap/utilite/UMath.h>
00047 #include <rtabmap/utilite/UConversion.h>
00048
00049 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
00050 #include <pcl/impl/instantiate.hpp>
00051 #include <pcl/point_types.h>
00052 #include <pcl/segmentation/impl/extract_clusters.hpp>
00053 #include <pcl/segmentation/extract_labeled_clusters.h>
00054 #include <pcl/segmentation/impl/extract_labeled_clusters.hpp>
00055
00056 PCL_INSTANTIATE(EuclideanClusterExtraction, (pcl::PointXYZRGBNormal))
00057 PCL_INSTANTIATE(extractEuclideanClusters, (pcl::PointXYZRGBNormal))
00058 PCL_INSTANTIATE(extractEuclideanClusters_indices, (pcl::PointXYZRGBNormal))
00059 #endif
00060
00061 namespace rtabmap
00062 {
00063
00064 namespace util3d
00065 {
00066
00067 cv::Mat downsample(
00068 const cv::Mat & cloud,
00069 int step)
00070 {
00071 UASSERT(step > 0);
00072 cv::Mat output;
00073 if(step <= 1 || cloud.cols <= step)
00074 {
00075
00076 output = cloud.clone();
00077 }
00078 else
00079 {
00080 int finalSize = cloud.cols/step;
00081 output = cv::Mat(1, finalSize, cloud.type());
00082 int oi = 0;
00083 for(int i=0; i<cloud.cols-step+1; i+=step)
00084 {
00085 cv::Mat(cloud, cv::Range::all(), cv::Range(i,i+1)).copyTo(cv::Mat(output, cv::Range::all(), cv::Range(oi,oi+1)));
00086 ++oi;
00087 }
00088 }
00089 return output;
00090 }
00091 pcl::PointCloud<pcl::PointXYZ>::Ptr downsample(
00092 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00093 int step)
00094 {
00095 UASSERT(step > 0);
00096 pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
00097 if(step <= 1 || (int)cloud->size() <= step)
00098 {
00099
00100 *output = *cloud;
00101 }
00102 else
00103 {
00104 int finalSize = int(cloud->size())/step;
00105 output->resize(finalSize);
00106 int oi = 0;
00107 for(unsigned int i=0; i<cloud->size()-step+1; i+=step)
00108 {
00109 (*output)[oi++] = cloud->at(i);
00110 }
00111 }
00112 return output;
00113 }
00114 pcl::PointCloud<pcl::PointXYZRGB>::Ptr downsample(
00115 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00116 int step)
00117 {
00118 UASSERT(step > 0);
00119 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGB>);
00120 if(step <= 1 || (int)cloud->size()<=step)
00121 {
00122
00123 *output = *cloud;
00124 }
00125 else
00126 {
00127 int finalSize = int(cloud->size())/step;
00128 output->resize(finalSize);
00129 int oi = 0;
00130 for(int i=0; i<(int)cloud->size()-step+1; i+=step)
00131 {
00132 (*output)[oi++] = cloud->at(i);
00133 }
00134 }
00135 return output;
00136 }
00137
00138 pcl::PointCloud<pcl::PointXYZ>::Ptr voxelize(
00139 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00140 const pcl::IndicesPtr & indices,
00141 float voxelSize)
00142 {
00143 UASSERT(voxelSize > 0.0f);
00144 pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
00145 pcl::VoxelGrid<pcl::PointXYZ> filter;
00146 filter.setLeafSize(voxelSize, voxelSize, voxelSize);
00147 filter.setInputCloud(cloud);
00148 if(indices->size())
00149 {
00150 filter.setIndices(indices);
00151 }
00152 filter.filter(*output);
00153 return output;
00154 }
00155 pcl::PointCloud<pcl::PointNormal>::Ptr voxelize(
00156 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00157 const pcl::IndicesPtr & indices,
00158 float voxelSize)
00159 {
00160 UASSERT(voxelSize > 0.0f);
00161 pcl::PointCloud<pcl::PointNormal>::Ptr output(new pcl::PointCloud<pcl::PointNormal>);
00162 pcl::VoxelGrid<pcl::PointNormal> filter;
00163 filter.setLeafSize(voxelSize, voxelSize, voxelSize);
00164 filter.setInputCloud(cloud);
00165 if(indices->size())
00166 {
00167 filter.setIndices(indices);
00168 }
00169 filter.filter(*output);
00170 return output;
00171 }
00172 pcl::PointCloud<pcl::PointXYZRGB>::Ptr voxelize(
00173 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00174 const pcl::IndicesPtr & indices,
00175 float voxelSize)
00176 {
00177 UASSERT(voxelSize > 0.0f);
00178 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGB>);
00179 pcl::VoxelGrid<pcl::PointXYZRGB> filter;
00180 filter.setLeafSize(voxelSize, voxelSize, voxelSize);
00181 filter.setInputCloud(cloud);
00182 if(indices->size())
00183 {
00184 filter.setIndices(indices);
00185 }
00186 filter.filter(*output);
00187 return output;
00188 }
00189 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr voxelize(
00190 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00191 const pcl::IndicesPtr & indices,
00192 float voxelSize)
00193 {
00194 UASSERT(voxelSize > 0.0f);
00195 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00196 pcl::VoxelGrid<pcl::PointXYZRGBNormal> filter;
00197 filter.setLeafSize(voxelSize, voxelSize, voxelSize);
00198 filter.setInputCloud(cloud);
00199 if(indices->size())
00200 {
00201 filter.setIndices(indices);
00202 }
00203 filter.filter(*output);
00204 return output;
00205 }
00206
00207 pcl::PointCloud<pcl::PointXYZ>::Ptr voxelize(
00208 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00209 float voxelSize)
00210 {
00211 pcl::IndicesPtr indices(new std::vector<int>);
00212 return voxelize(cloud, indices, voxelSize);
00213 }
00214 pcl::PointCloud<pcl::PointNormal>::Ptr voxelize(
00215 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00216 float voxelSize)
00217 {
00218 pcl::IndicesPtr indices(new std::vector<int>);
00219 return voxelize(cloud, indices, voxelSize);
00220 }
00221 pcl::PointCloud<pcl::PointXYZRGB>::Ptr voxelize(
00222 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00223 float voxelSize)
00224 {
00225 pcl::IndicesPtr indices(new std::vector<int>);
00226 return voxelize(cloud, indices, voxelSize);
00227 }
00228 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr voxelize(
00229 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00230 float voxelSize)
00231 {
00232 pcl::IndicesPtr indices(new std::vector<int>);
00233 return voxelize(cloud, indices, voxelSize);
00234 }
00235
00236
00237 pcl::PointCloud<pcl::PointXYZ>::Ptr randomSampling(
00238 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud, int samples)
00239 {
00240 UASSERT(samples > 0);
00241 pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
00242 pcl::RandomSample<pcl::PointXYZ> filter;
00243 filter.setSample(samples);
00244 filter.setInputCloud(cloud);
00245 filter.filter(*output);
00246 return output;
00247 }
00248 pcl::PointCloud<pcl::PointXYZRGB>::Ptr randomSampling(
00249 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud, int samples)
00250 {
00251 UASSERT(samples > 0);
00252 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGB>);
00253 pcl::RandomSample<pcl::PointXYZRGB> filter;
00254 filter.setSample(samples);
00255 filter.setInputCloud(cloud);
00256 filter.filter(*output);
00257 return output;
00258 }
00259
00260 pcl::IndicesPtr passThrough(
00261 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00262 const pcl::IndicesPtr & indices,
00263 const std::string & axis,
00264 float min,
00265 float max,
00266 bool negative)
00267 {
00268 UASSERT(max > min);
00269 UASSERT(axis.compare("x") == 0 || axis.compare("y") == 0 || axis.compare("z") == 0);
00270
00271 pcl::IndicesPtr output(new std::vector<int>);
00272 pcl::PassThrough<pcl::PointXYZ> filter;
00273 filter.setNegative(negative);
00274 filter.setFilterFieldName(axis);
00275 filter.setFilterLimits(min, max);
00276 filter.setInputCloud(cloud);
00277 filter.setIndices(indices);
00278 filter.filter(*output);
00279 return output;
00280 }
00281 pcl::IndicesPtr passThrough(
00282 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00283 const pcl::IndicesPtr & indices,
00284 const std::string & axis,
00285 float min,
00286 float max,
00287 bool negative)
00288 {
00289 UASSERT(max > min);
00290 UASSERT(axis.compare("x") == 0 || axis.compare("y") == 0 || axis.compare("z") == 0);
00291
00292 pcl::IndicesPtr output(new std::vector<int>);
00293 pcl::PassThrough<pcl::PointXYZRGB> filter;
00294 filter.setNegative(negative);
00295 filter.setFilterFieldName(axis);
00296 filter.setFilterLimits(min, max);
00297 filter.setInputCloud(cloud);
00298 filter.setIndices(indices);
00299 filter.filter(*output);
00300 return output;
00301 }
00302
00303 pcl::PointCloud<pcl::PointXYZ>::Ptr passThrough(
00304 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00305 const std::string & axis,
00306 float min,
00307 float max,
00308 bool negative)
00309 {
00310 UASSERT(max > min);
00311 UASSERT(axis.compare("x") == 0 || axis.compare("y") == 0 || axis.compare("z") == 0);
00312
00313 pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
00314 pcl::PassThrough<pcl::PointXYZ> filter;
00315 filter.setNegative(negative);
00316 filter.setFilterFieldName(axis);
00317 filter.setFilterLimits(min, max);
00318 filter.setInputCloud(cloud);
00319 filter.filter(*output);
00320 return output;
00321 }
00322
00323 pcl::PointCloud<pcl::PointXYZRGB>::Ptr passThrough(
00324 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00325 const std::string & axis,
00326 float min,
00327 float max,
00328 bool negative)
00329 {
00330 UASSERT(max > min);
00331 UASSERT(axis.compare("x") == 0 || axis.compare("y") == 0 || axis.compare("z") == 0);
00332
00333 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGB>);
00334 pcl::PassThrough<pcl::PointXYZRGB> filter;
00335 filter.setNegative(negative);
00336 filter.setFilterFieldName(axis);
00337 filter.setFilterLimits(min, max);
00338 filter.setInputCloud(cloud);
00339 filter.filter(*output);
00340 return output;
00341 }
00342
00343 pcl::IndicesPtr frustumFiltering(
00344 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00345 const pcl::IndicesPtr & indices,
00346 const Transform & cameraPose,
00347 float horizontalFOV,
00348 float verticalFOV,
00349 float nearClipPlaneDistance,
00350 float farClipPlaneDistance,
00351 bool negative)
00352 {
00353 UASSERT(horizontalFOV > 0.0f && verticalFOV > 0.0f);
00354 UASSERT(farClipPlaneDistance > nearClipPlaneDistance);
00355 UASSERT(!cameraPose.isNull());
00356
00357 pcl::IndicesPtr output(new std::vector<int>);
00358 pcl::FrustumCulling<pcl::PointXYZ> fc;
00359 fc.setNegative(negative);
00360 fc.setInputCloud (cloud);
00361 if(indices.get() && indices->size())
00362 {
00363 fc.setIndices(indices);
00364 }
00365 fc.setVerticalFOV (verticalFOV);
00366 fc.setHorizontalFOV (horizontalFOV);
00367 fc.setNearPlaneDistance (nearClipPlaneDistance);
00368 fc.setFarPlaneDistance (farClipPlaneDistance);
00369
00370 fc.setCameraPose (cameraPose.toEigen4f());
00371 fc.filter (*output);
00372
00373 return output;
00374 }
00375
00376 pcl::PointCloud<pcl::PointXYZ>::Ptr frustumFiltering(
00377 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00378 const Transform & cameraPose,
00379 float horizontalFOV,
00380 float verticalFOV,
00381 float nearClipPlaneDistance,
00382 float farClipPlaneDistance,
00383 bool negative)
00384 {
00385 UASSERT(horizontalFOV > 0.0f && verticalFOV > 0.0f);
00386 UASSERT(farClipPlaneDistance > nearClipPlaneDistance);
00387 UASSERT(!cameraPose.isNull());
00388
00389 pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
00390 pcl::FrustumCulling<pcl::PointXYZ> fc;
00391 fc.setNegative(negative);
00392 fc.setInputCloud (cloud);
00393 fc.setVerticalFOV (verticalFOV);
00394 fc.setHorizontalFOV (horizontalFOV);
00395 fc.setNearPlaneDistance (nearClipPlaneDistance);
00396 fc.setFarPlaneDistance (farClipPlaneDistance);
00397
00398 fc.setCameraPose (cameraPose.toEigen4f());
00399 fc.filter (*output);
00400
00401 return output;
00402 }
00403
00404 pcl::PointCloud<pcl::PointXYZRGB>::Ptr frustumFiltering(
00405 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00406 const Transform & cameraPose,
00407 float horizontalFOV,
00408 float verticalFOV,
00409 float nearClipPlaneDistance,
00410 float farClipPlaneDistance,
00411 bool negative)
00412 {
00413 UASSERT(horizontalFOV > 0.0f && verticalFOV > 0.0f);
00414 UASSERT(farClipPlaneDistance > nearClipPlaneDistance);
00415 UASSERT(!cameraPose.isNull());
00416
00417 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGB>);
00418 pcl::FrustumCulling<pcl::PointXYZRGB> fc;
00419 fc.setNegative(negative);
00420 fc.setInputCloud (cloud);
00421 fc.setVerticalFOV (verticalFOV);
00422 fc.setHorizontalFOV (horizontalFOV);
00423 fc.setNearPlaneDistance (nearClipPlaneDistance);
00424 fc.setFarPlaneDistance (farClipPlaneDistance);
00425
00426 fc.setCameraPose (cameraPose.toEigen4f());
00427 fc.filter (*output);
00428
00429 return output;
00430 }
00431
00432
00433 pcl::PointCloud<pcl::PointXYZ>::Ptr removeNaNFromPointCloud(
00434 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud)
00435 {
00436 pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
00437 std::vector<int> indices;
00438 pcl::removeNaNFromPointCloud(*cloud, *output, indices);
00439 return output;
00440 }
00441 pcl::PointCloud<pcl::PointXYZRGB>::Ptr removeNaNFromPointCloud(
00442 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud)
00443 {
00444 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGB>);
00445 std::vector<int> indices;
00446 pcl::removeNaNFromPointCloud(*cloud, *output, indices);
00447 return output;
00448 }
00449
00450
00451 pcl::PointCloud<pcl::PointNormal>::Ptr removeNaNNormalsFromPointCloud(
00452 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud)
00453 {
00454 pcl::PointCloud<pcl::PointNormal>::Ptr output(new pcl::PointCloud<pcl::PointNormal>);
00455 std::vector<int> indices;
00456 pcl::removeNaNNormalsFromPointCloud(*cloud, *output, indices);
00457 return output;
00458 }
00459 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr removeNaNNormalsFromPointCloud(
00460 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud)
00461 {
00462 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00463 std::vector<int> indices;
00464 pcl::removeNaNNormalsFromPointCloud(*cloud, *output, indices);
00465 return output;
00466 }
00467
00468
00469
00470 pcl::IndicesPtr radiusFiltering(
00471 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00472 float radiusSearch,
00473 int minNeighborsInRadius)
00474 {
00475 pcl::IndicesPtr indices(new std::vector<int>);
00476 return radiusFiltering(cloud, indices, radiusSearch, minNeighborsInRadius);
00477 }
00478 pcl::IndicesPtr radiusFiltering(
00479 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00480 float radiusSearch,
00481 int minNeighborsInRadius)
00482 {
00483 pcl::IndicesPtr indices(new std::vector<int>);
00484 return radiusFiltering(cloud, indices, radiusSearch, minNeighborsInRadius);
00485 }
00486 pcl::IndicesPtr radiusFiltering(
00487 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00488 float radiusSearch,
00489 int minNeighborsInRadius)
00490 {
00491 pcl::IndicesPtr indices(new std::vector<int>);
00492 return radiusFiltering(cloud, indices, radiusSearch, minNeighborsInRadius);
00493 }
00494 pcl::IndicesPtr radiusFiltering(
00495 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00496 float radiusSearch,
00497 int minNeighborsInRadius)
00498 {
00499 pcl::IndicesPtr indices(new std::vector<int>);
00500 return radiusFiltering(cloud, indices, radiusSearch, minNeighborsInRadius);
00501 }
00502
00503
00504 pcl::IndicesPtr radiusFiltering(
00505 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00506 const pcl::IndicesPtr & indices,
00507 float radiusSearch,
00508 int minNeighborsInRadius)
00509 {
00510 pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>(false));
00511
00512 if(indices->size())
00513 {
00514 pcl::IndicesPtr output(new std::vector<int>(indices->size()));
00515 int oi = 0;
00516 tree->setInputCloud(cloud, indices);
00517 for(unsigned int i=0; i<indices->size(); ++i)
00518 {
00519 std::vector<int> kIndices;
00520 std::vector<float> kDistances;
00521 int k = tree->radiusSearch(cloud->at(indices->at(i)), radiusSearch, kIndices, kDistances);
00522 if(k > minNeighborsInRadius)
00523 {
00524 output->at(oi++) = indices->at(i);
00525 }
00526 }
00527 output->resize(oi);
00528 return output;
00529 }
00530 else
00531 {
00532 pcl::IndicesPtr output(new std::vector<int>(cloud->size()));
00533 int oi = 0;
00534 tree->setInputCloud(cloud);
00535 for(unsigned int i=0; i<cloud->size(); ++i)
00536 {
00537 std::vector<int> kIndices;
00538 std::vector<float> kDistances;
00539 int k = tree->radiusSearch(cloud->at(i), radiusSearch, kIndices, kDistances);
00540 if(k > minNeighborsInRadius)
00541 {
00542 output->at(oi++) = i;
00543 }
00544 }
00545 output->resize(oi);
00546 return output;
00547 }
00548 }
00549 pcl::IndicesPtr radiusFiltering(
00550 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00551 const pcl::IndicesPtr & indices,
00552 float radiusSearch,
00553 int minNeighborsInRadius)
00554 {
00555 pcl::search::KdTree<pcl::PointNormal>::Ptr tree (new pcl::search::KdTree<pcl::PointNormal>(false));
00556
00557 if(indices->size())
00558 {
00559 pcl::IndicesPtr output(new std::vector<int>(indices->size()));
00560 int oi = 0;
00561 tree->setInputCloud(cloud, indices);
00562 for(unsigned int i=0; i<indices->size(); ++i)
00563 {
00564 std::vector<int> kIndices;
00565 std::vector<float> kDistances;
00566 int k = tree->radiusSearch(cloud->at(indices->at(i)), radiusSearch, kIndices, kDistances);
00567 if(k > minNeighborsInRadius)
00568 {
00569 output->at(oi++) = indices->at(i);
00570 }
00571 }
00572 output->resize(oi);
00573 return output;
00574 }
00575 else
00576 {
00577 pcl::IndicesPtr output(new std::vector<int>(cloud->size()));
00578 int oi = 0;
00579 tree->setInputCloud(cloud);
00580 for(unsigned int i=0; i<cloud->size(); ++i)
00581 {
00582 std::vector<int> kIndices;
00583 std::vector<float> kDistances;
00584 int k = tree->radiusSearch(cloud->at(i), radiusSearch, kIndices, kDistances);
00585 if(k > minNeighborsInRadius)
00586 {
00587 output->at(oi++) = i;
00588 }
00589 }
00590 output->resize(oi);
00591 return output;
00592 }
00593 }
00594 pcl::IndicesPtr radiusFiltering(
00595 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00596 const pcl::IndicesPtr & indices,
00597 float radiusSearch,
00598 int minNeighborsInRadius)
00599 {
00600 pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGB>(false));
00601
00602 if(indices->size())
00603 {
00604 pcl::IndicesPtr output(new std::vector<int>(indices->size()));
00605 int oi = 0;
00606 tree->setInputCloud(cloud, indices);
00607 for(unsigned int i=0; i<indices->size(); ++i)
00608 {
00609 std::vector<int> kIndices;
00610 std::vector<float> kDistances;
00611 int k = tree->radiusSearch(cloud->at(indices->at(i)), radiusSearch, kIndices, kDistances);
00612 if(k > minNeighborsInRadius)
00613 {
00614 output->at(oi++) = indices->at(i);
00615 }
00616 }
00617 output->resize(oi);
00618 return output;
00619 }
00620 else
00621 {
00622 pcl::IndicesPtr output(new std::vector<int>(cloud->size()));
00623 int oi = 0;
00624 tree->setInputCloud(cloud);
00625 for(unsigned int i=0; i<cloud->size(); ++i)
00626 {
00627 std::vector<int> kIndices;
00628 std::vector<float> kDistances;
00629 int k = tree->radiusSearch(cloud->at(i), radiusSearch, kIndices, kDistances);
00630 if(k > minNeighborsInRadius)
00631 {
00632 output->at(oi++) = i;
00633 }
00634 }
00635 output->resize(oi);
00636 return output;
00637 }
00638 }
00639 pcl::IndicesPtr radiusFiltering(
00640 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00641 const pcl::IndicesPtr & indices,
00642 float radiusSearch,
00643 int minNeighborsInRadius)
00644 {
00645 pcl::search::KdTree<pcl::PointXYZRGBNormal>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGBNormal>(false));
00646
00647 if(indices->size())
00648 {
00649 pcl::IndicesPtr output(new std::vector<int>(indices->size()));
00650 int oi = 0;
00651 tree->setInputCloud(cloud, indices);
00652 for(unsigned int i=0; i<indices->size(); ++i)
00653 {
00654 std::vector<int> kIndices;
00655 std::vector<float> kDistances;
00656 int k = tree->radiusSearch(cloud->at(indices->at(i)), radiusSearch, kIndices, kDistances);
00657 if(k > minNeighborsInRadius)
00658 {
00659 output->at(oi++) = indices->at(i);
00660 }
00661 }
00662 output->resize(oi);
00663 return output;
00664 }
00665 else
00666 {
00667 pcl::IndicesPtr output(new std::vector<int>(cloud->size()));
00668 int oi = 0;
00669 tree->setInputCloud(cloud);
00670 for(unsigned int i=0; i<cloud->size(); ++i)
00671 {
00672 std::vector<int> kIndices;
00673 std::vector<float> kDistances;
00674 int k = tree->radiusSearch(cloud->at(i), radiusSearch, kIndices, kDistances);
00675 if(k > minNeighborsInRadius)
00676 {
00677 output->at(oi++) = i;
00678 }
00679 }
00680 output->resize(oi);
00681 return output;
00682 }
00683 }
00684
00685 pcl::PointCloud<pcl::PointXYZRGB>::Ptr subtractFiltering(
00686 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00687 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
00688 float radiusSearch,
00689 int minNeighborsInRadius)
00690 {
00691 pcl::IndicesPtr indices(new std::vector<int>);
00692 pcl::IndicesPtr indicesOut = subtractFiltering(cloud, indices, substractCloud, indices, radiusSearch, minNeighborsInRadius);
00693 pcl::PointCloud<pcl::PointXYZRGB>::Ptr out(new pcl::PointCloud<pcl::PointXYZRGB>);
00694 pcl::copyPointCloud(*cloud, *indicesOut, *out);
00695 return out;
00696 }
00697
00698
00699 pcl::IndicesPtr subtractFiltering(
00700 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00701 const pcl::IndicesPtr & indices,
00702 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
00703 const pcl::IndicesPtr & substractIndices,
00704 float radiusSearch,
00705 int minNeighborsInRadius)
00706 {
00707 UASSERT(minNeighborsInRadius > 0);
00708 pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGB>(false));
00709
00710 if(indices->size())
00711 {
00712 pcl::IndicesPtr output(new std::vector<int>(indices->size()));
00713 int oi = 0;
00714 if(substractIndices->size())
00715 {
00716 tree->setInputCloud(substractCloud, substractIndices);
00717 }
00718 else
00719 {
00720 tree->setInputCloud(substractCloud);
00721 }
00722 for(unsigned int i=0; i<indices->size(); ++i)
00723 {
00724 std::vector<int> kIndices;
00725 std::vector<float> kDistances;
00726 int k = tree->radiusSearch(cloud->at(indices->at(i)), radiusSearch, kIndices, kDistances);
00727 if(k < minNeighborsInRadius)
00728 {
00729 output->at(oi++) = indices->at(i);
00730 }
00731 }
00732 output->resize(oi);
00733 return output;
00734 }
00735 else
00736 {
00737 pcl::IndicesPtr output(new std::vector<int>(cloud->size()));
00738 int oi = 0;
00739 if(substractIndices->size())
00740 {
00741 tree->setInputCloud(substractCloud, substractIndices);
00742 }
00743 else
00744 {
00745 tree->setInputCloud(substractCloud);
00746 }
00747 for(unsigned int i=0; i<cloud->size(); ++i)
00748 {
00749 std::vector<int> kIndices;
00750 std::vector<float> kDistances;
00751 int k = tree->radiusSearch(cloud->at(i), radiusSearch, kIndices, kDistances);
00752 if(k < minNeighborsInRadius)
00753 {
00754 output->at(oi++) = i;
00755 }
00756 }
00757 output->resize(oi);
00758 return output;
00759 }
00760 }
00761
00762 pcl::PointCloud<pcl::PointNormal>::Ptr subtractFiltering(
00763 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00764 const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
00765 float radiusSearch,
00766 float maxAngle,
00767 int minNeighborsInRadius)
00768 {
00769 pcl::IndicesPtr indices(new std::vector<int>);
00770 pcl::IndicesPtr indicesOut = subtractFiltering(cloud, indices, substractCloud, indices, radiusSearch, maxAngle, minNeighborsInRadius);
00771 pcl::PointCloud<pcl::PointNormal>::Ptr out(new pcl::PointCloud<pcl::PointNormal>);
00772 pcl::copyPointCloud(*cloud, *indicesOut, *out);
00773 return out;
00774 }
00775
00776
00777 pcl::IndicesPtr subtractFiltering(
00778 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00779 const pcl::IndicesPtr & indices,
00780 const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
00781 const pcl::IndicesPtr & substractIndices,
00782 float radiusSearch,
00783 float maxAngle,
00784 int minNeighborsInRadius)
00785 {
00786 UASSERT(minNeighborsInRadius > 0);
00787 pcl::search::KdTree<pcl::PointNormal>::Ptr tree (new pcl::search::KdTree<pcl::PointNormal>(false));
00788
00789 if(indices->size())
00790 {
00791 pcl::IndicesPtr output(new std::vector<int>(indices->size()));
00792 int oi = 0;
00793 if(substractIndices->size())
00794 {
00795 tree->setInputCloud(substractCloud, substractIndices);
00796 }
00797 else
00798 {
00799 tree->setInputCloud(substractCloud);
00800 }
00801 for(unsigned int i=0; i<indices->size(); ++i)
00802 {
00803 std::vector<int> kIndices;
00804 std::vector<float> kDistances;
00805 int k = tree->radiusSearch(cloud->at(indices->at(i)), radiusSearch, kIndices, kDistances);
00806 if(k>=minNeighborsInRadius && maxAngle > 0.0f)
00807 {
00808 Eigen::Vector4f normal(cloud->at(indices->at(i)).normal_x, cloud->at(indices->at(i)).normal_y, cloud->at(indices->at(i)).normal_z, 0.0f);
00809 if (uIsFinite(normal[0]) &&
00810 uIsFinite(normal[1]) &&
00811 uIsFinite(normal[2]))
00812 {
00813 int count = k;
00814 for(int j=0; j<count && k >= minNeighborsInRadius; ++j)
00815 {
00816 Eigen::Vector4f v(substractCloud->at(kIndices.at(j)).normal_x, substractCloud->at(kIndices.at(j)).normal_y, substractCloud->at(kIndices.at(j)).normal_z, 0.0f);
00817 if(uIsFinite(v[0]) &&
00818 uIsFinite(v[1]) &&
00819 uIsFinite(v[2]))
00820 {
00821 float angle = pcl::getAngle3D(normal, v);
00822 if(angle > maxAngle)
00823 {
00824 k-=1;
00825 }
00826 }
00827 else
00828 {
00829 k-=1;
00830 }
00831 }
00832 }
00833 else
00834 {
00835 k=0;
00836 }
00837 }
00838 if(k < minNeighborsInRadius)
00839 {
00840 output->at(oi++) = indices->at(i);
00841 }
00842 }
00843 output->resize(oi);
00844 return output;
00845 }
00846 else
00847 {
00848 pcl::IndicesPtr output(new std::vector<int>(cloud->size()));
00849 int oi = 0;
00850 if(substractIndices->size())
00851 {
00852 tree->setInputCloud(substractCloud, substractIndices);
00853 }
00854 else
00855 {
00856 tree->setInputCloud(substractCloud);
00857 }
00858 for(unsigned int i=0; i<cloud->size(); ++i)
00859 {
00860 std::vector<int> kIndices;
00861 std::vector<float> kDistances;
00862 int k = tree->radiusSearch(cloud->at(i), radiusSearch, kIndices, kDistances);
00863 if(k>=minNeighborsInRadius && maxAngle > 0.0f)
00864 {
00865 Eigen::Vector4f normal(cloud->at(i).normal_x, cloud->at(i).normal_y, cloud->at(i).normal_z, 0.0f);
00866 if (uIsFinite(normal[0]) &&
00867 uIsFinite(normal[1]) &&
00868 uIsFinite(normal[2]))
00869 {
00870 int count = k;
00871 for(int j=0; j<count && k >= minNeighborsInRadius; ++j)
00872 {
00873 Eigen::Vector4f v(substractCloud->at(kIndices.at(j)).normal_x, substractCloud->at(kIndices.at(j)).normal_y, substractCloud->at(kIndices.at(j)).normal_z, 0.0f);
00874 if(uIsFinite(v[0]) &&
00875 uIsFinite(v[1]) &&
00876 uIsFinite(v[2]))
00877 {
00878 float angle = pcl::getAngle3D(normal, v);
00879 if(angle > maxAngle)
00880 {
00881 k-=1;
00882 }
00883 }
00884 else
00885 {
00886 k-=1;
00887 }
00888 }
00889 }
00890 else
00891 {
00892 k=0;
00893 }
00894 }
00895 if(k < minNeighborsInRadius)
00896 {
00897 output->at(oi++) = i;
00898 }
00899 }
00900 output->resize(oi);
00901 return output;
00902 }
00903 }
00904
00905 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr subtractFiltering(
00906 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00907 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
00908 float radiusSearch,
00909 float maxAngle,
00910 int minNeighborsInRadius)
00911 {
00912 pcl::IndicesPtr indices(new std::vector<int>);
00913 pcl::IndicesPtr indicesOut = subtractFiltering(cloud, indices, substractCloud, indices, radiusSearch, maxAngle, minNeighborsInRadius);
00914 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr out(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00915 pcl::copyPointCloud(*cloud, *indicesOut, *out);
00916 return out;
00917 }
00918
00919
00920 pcl::IndicesPtr subtractFiltering(
00921 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00922 const pcl::IndicesPtr & indices,
00923 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
00924 const pcl::IndicesPtr & substractIndices,
00925 float radiusSearch,
00926 float maxAngle,
00927 int minNeighborsInRadius)
00928 {
00929 UASSERT(minNeighborsInRadius > 0);
00930 pcl::search::KdTree<pcl::PointXYZRGBNormal>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGBNormal>(false));
00931
00932 if(indices->size())
00933 {
00934 pcl::IndicesPtr output(new std::vector<int>(indices->size()));
00935 int oi = 0;
00936 if(substractIndices->size())
00937 {
00938 tree->setInputCloud(substractCloud, substractIndices);
00939 }
00940 else
00941 {
00942 tree->setInputCloud(substractCloud);
00943 }
00944 for(unsigned int i=0; i<indices->size(); ++i)
00945 {
00946 std::vector<int> kIndices;
00947 std::vector<float> kDistances;
00948 int k = tree->radiusSearch(cloud->at(indices->at(i)), radiusSearch, kIndices, kDistances);
00949 if(k>=minNeighborsInRadius && maxAngle > 0.0f)
00950 {
00951 Eigen::Vector4f normal(cloud->at(indices->at(i)).normal_x, cloud->at(indices->at(i)).normal_y, cloud->at(indices->at(i)).normal_z, 0.0f);
00952 if (uIsFinite(normal[0]) &&
00953 uIsFinite(normal[1]) &&
00954 uIsFinite(normal[2]))
00955 {
00956 int count = k;
00957 for(int j=0; j<count && k >= minNeighborsInRadius; ++j)
00958 {
00959 Eigen::Vector4f v(substractCloud->at(kIndices.at(j)).normal_x, substractCloud->at(kIndices.at(j)).normal_y, substractCloud->at(kIndices.at(j)).normal_z, 0.0f);
00960 if(uIsFinite(v[0]) &&
00961 uIsFinite(v[1]) &&
00962 uIsFinite(v[2]))
00963 {
00964 float angle = pcl::getAngle3D(normal, v);
00965 if(angle > maxAngle)
00966 {
00967 k-=1;
00968 }
00969 }
00970 else
00971 {
00972 k-=1;
00973 }
00974 }
00975 }
00976 else
00977 {
00978 k=0;
00979 }
00980 }
00981 if(k < minNeighborsInRadius)
00982 {
00983 output->at(oi++) = indices->at(i);
00984 }
00985 }
00986 output->resize(oi);
00987 return output;
00988 }
00989 else
00990 {
00991 pcl::IndicesPtr output(new std::vector<int>(cloud->size()));
00992 int oi = 0;
00993 if(substractIndices->size())
00994 {
00995 tree->setInputCloud(substractCloud, substractIndices);
00996 }
00997 else
00998 {
00999 tree->setInputCloud(substractCloud);
01000 }
01001 for(unsigned int i=0; i<cloud->size(); ++i)
01002 {
01003 std::vector<int> kIndices;
01004 std::vector<float> kDistances;
01005 int k = tree->radiusSearch(cloud->at(i), radiusSearch, kIndices, kDistances);
01006 if(k>=minNeighborsInRadius && maxAngle > 0.0f)
01007 {
01008 Eigen::Vector4f normal(cloud->at(i).normal_x, cloud->at(i).normal_y, cloud->at(i).normal_z, 0.0f);
01009 if (uIsFinite(normal[0]) &&
01010 uIsFinite(normal[1]) &&
01011 uIsFinite(normal[2]))
01012 {
01013 int count = k;
01014 for(int j=0; j<count && k >= minNeighborsInRadius; ++j)
01015 {
01016 Eigen::Vector4f v(substractCloud->at(kIndices.at(j)).normal_x, substractCloud->at(kIndices.at(j)).normal_y, substractCloud->at(kIndices.at(j)).normal_z, 0.0f);
01017 if(uIsFinite(v[0]) &&
01018 uIsFinite(v[1]) &&
01019 uIsFinite(v[2]))
01020 {
01021 float angle = pcl::getAngle3D(normal, v);
01022 if(angle > maxAngle)
01023 {
01024 k-=1;
01025 }
01026 }
01027 else
01028 {
01029 k-=1;
01030 }
01031 }
01032 }
01033 else
01034 {
01035 k=0;
01036 }
01037 }
01038 if(k < minNeighborsInRadius)
01039 {
01040 output->at(oi++) = i;
01041 }
01042 }
01043 output->resize(oi);
01044 return output;
01045 }
01046 }
01047
01048 pcl::IndicesPtr subtractAdaptiveFiltering(
01049 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
01050 const pcl::IndicesPtr & indices,
01051 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
01052 const pcl::IndicesPtr & substractIndices,
01053 float radiusSearchRatio,
01054 int minNeighborsInRadius,
01055 const Eigen::Vector3f & viewpoint)
01056 {
01057 UWARN("Add angle to avoid subtraction of points with opposite normals");
01058 UASSERT(minNeighborsInRadius > 0);
01059 UASSERT(radiusSearchRatio > 0.0f);
01060 pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGB>(false));
01061
01062 if(indices->size())
01063 {
01064 pcl::IndicesPtr output(new std::vector<int>(indices->size()));
01065 int oi = 0;
01066 if(substractIndices->size())
01067 {
01068 tree->setInputCloud(substractCloud, substractIndices);
01069 }
01070 else
01071 {
01072 tree->setInputCloud(substractCloud);
01073 }
01074 for(unsigned int i=0; i<indices->size(); ++i)
01075 {
01076 if(pcl::isFinite(cloud->at(indices->at(i))))
01077 {
01078 std::vector<int> kIndices;
01079 std::vector<float> kSqrdDistances;
01080 float radius = radiusSearchRatio*uNorm(
01081 cloud->at(indices->at(i)).x-viewpoint[0],
01082 cloud->at(indices->at(i)).y-viewpoint[1],
01083 cloud->at(indices->at(i)).z-viewpoint[2]);
01084 int k = tree->radiusSearch(cloud->at(indices->at(i)), radius, kIndices, kSqrdDistances);
01085 if(k < minNeighborsInRadius)
01086 {
01087 output->at(oi++) = indices->at(i);
01088 }
01089 }
01090 }
01091 output->resize(oi);
01092 return output;
01093 }
01094 else
01095 {
01096 pcl::IndicesPtr output(new std::vector<int>(cloud->size()));
01097 int oi = 0;
01098 if(substractIndices->size())
01099 {
01100 tree->setInputCloud(substractCloud, substractIndices);
01101 }
01102 else
01103 {
01104 tree->setInputCloud(substractCloud);
01105 }
01106 for(unsigned int i=0; i<cloud->size(); ++i)
01107 {
01108 if(pcl::isFinite(cloud->at(i)))
01109 {
01110 std::vector<int> kIndices;
01111 std::vector<float> kSqrdDistances;
01112 float radius = radiusSearchRatio*uNorm(
01113 cloud->at(i).x-viewpoint[0],
01114 cloud->at(i).y-viewpoint[1],
01115 cloud->at(i).z-viewpoint[2]);
01116 int k = tree->radiusSearch(cloud->at(i), radius, kIndices, kSqrdDistances);
01117 if(k < minNeighborsInRadius)
01118 {
01119 output->at(oi++) = i;
01120 }
01121 }
01122 }
01123 output->resize(oi);
01124 return output;
01125 }
01126 }
01127 pcl::IndicesPtr subtractAdaptiveFiltering(
01128 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
01129 const pcl::IndicesPtr & indices,
01130 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
01131 const pcl::IndicesPtr & substractIndices,
01132 float radiusSearchRatio,
01133 float maxAngle,
01134 int minNeighborsInRadius,
01135 const Eigen::Vector3f & viewpoint)
01136 {
01137 UASSERT(minNeighborsInRadius > 0);
01138 UASSERT(radiusSearchRatio > 0.0f);
01139 pcl::search::KdTree<pcl::PointXYZRGBNormal>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGBNormal>(false));
01140
01141 if(indices->size())
01142 {
01143 pcl::IndicesPtr output(new std::vector<int>(indices->size()));
01144 int oi = 0;
01145 if(substractIndices->size())
01146 {
01147 tree->setInputCloud(substractCloud, substractIndices);
01148 }
01149 else
01150 {
01151 tree->setInputCloud(substractCloud);
01152 }
01153 for(unsigned int i=0; i<indices->size(); ++i)
01154 {
01155 if(pcl::isFinite(cloud->at(indices->at(i))))
01156 {
01157 std::vector<int> kIndices;
01158 std::vector<float> kSqrdDistances;
01159 float radius = radiusSearchRatio*uNorm(
01160 cloud->at(indices->at(i)).x-viewpoint[0],
01161 cloud->at(indices->at(i)).y-viewpoint[1],
01162 cloud->at(indices->at(i)).z-viewpoint[2]);
01163 int k = tree->radiusSearch(cloud->at(indices->at(i)), radius, kIndices, kSqrdDistances);
01164 if(k>=minNeighborsInRadius && maxAngle > 0.0f)
01165 {
01166 Eigen::Vector4f normal(cloud->at(indices->at(i)).normal_x, cloud->at(indices->at(i)).normal_y, cloud->at(indices->at(i)).normal_z, 0.0f);
01167 if (uIsFinite(normal[0]) &&
01168 uIsFinite(normal[1]) &&
01169 uIsFinite(normal[2]))
01170 {
01171 int count = k;
01172 for(int j=0; j<count && k >= minNeighborsInRadius; ++j)
01173 {
01174 Eigen::Vector4f v(substractCloud->at(kIndices.at(j)).normal_x, substractCloud->at(kIndices.at(j)).normal_y, substractCloud->at(kIndices.at(j)).normal_z, 0.0f);
01175 if(uIsFinite(v[0]) &&
01176 uIsFinite(v[1]) &&
01177 uIsFinite(v[2]))
01178 {
01179 float angle = pcl::getAngle3D(normal, v);
01180 if(angle > maxAngle)
01181 {
01182 k-=1;
01183 }
01184 }
01185 else
01186 {
01187 k-=1;
01188 }
01189 }
01190 }
01191 else
01192 {
01193 k=0;
01194 }
01195 }
01196
01197 if(k < minNeighborsInRadius)
01198 {
01199 output->at(oi++) = indices->at(i);
01200 }
01201 }
01202 }
01203 output->resize(oi);
01204 return output;
01205 }
01206 else
01207 {
01208 pcl::IndicesPtr output(new std::vector<int>(cloud->size()));
01209 int oi = 0;
01210 if(substractIndices->size())
01211 {
01212 tree->setInputCloud(substractCloud, substractIndices);
01213 }
01214 else
01215 {
01216 tree->setInputCloud(substractCloud);
01217 }
01218 for(unsigned int i=0; i<cloud->size(); ++i)
01219 {
01220 if(pcl::isFinite(cloud->at(i)))
01221 {
01222 std::vector<int> kIndices;
01223 std::vector<float> kSqrdDistances;
01224 float radius = radiusSearchRatio*uNorm(
01225 cloud->at(i).x-viewpoint[0],
01226 cloud->at(i).y-viewpoint[1],
01227 cloud->at(i).z-viewpoint[2]);
01228 int k = tree->radiusSearch(cloud->at(i), radius, kIndices, kSqrdDistances);
01229 if(k>=minNeighborsInRadius && maxAngle > 0.0f)
01230 {
01231 Eigen::Vector4f normal(cloud->at(i).normal_x, cloud->at(i).normal_y, cloud->at(i).normal_z, 0.0f);
01232 if (uIsFinite(normal[0]) &&
01233 uIsFinite(normal[1]) &&
01234 uIsFinite(normal[2]))
01235 {
01236 int count = k;
01237 for(int j=0; j<count && k >= minNeighborsInRadius; ++j)
01238 {
01239 Eigen::Vector4f v(substractCloud->at(kIndices.at(j)).normal_x, substractCloud->at(kIndices.at(j)).normal_y, substractCloud->at(kIndices.at(j)).normal_z, 0.0f);
01240 if(uIsFinite(v[0]) &&
01241 uIsFinite(v[1]) &&
01242 uIsFinite(v[2]))
01243 {
01244 float angle = pcl::getAngle3D(normal, v);
01245 if(angle > maxAngle)
01246 {
01247 k-=1;
01248 }
01249 }
01250 else
01251 {
01252 k-=1;
01253 }
01254 }
01255 }
01256 else
01257 {
01258 k=0;
01259 }
01260 }
01261 if(k < minNeighborsInRadius)
01262 {
01263 output->at(oi++) = i;
01264 }
01265 }
01266 }
01267 output->resize(oi);
01268 return output;
01269 }
01270 }
01271
01272
01273 pcl::IndicesPtr normalFiltering(
01274 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
01275 float angleMax,
01276 const Eigen::Vector4f & normal,
01277 int normalKSearch,
01278 const Eigen::Vector4f & viewpoint)
01279 {
01280 pcl::IndicesPtr indices(new std::vector<int>);
01281 return normalFiltering(cloud, indices, angleMax, normal, normalKSearch, viewpoint);
01282 }
01283 pcl::IndicesPtr normalFiltering(
01284 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
01285 float angleMax,
01286 const Eigen::Vector4f & normal,
01287 int normalKSearch,
01288 const Eigen::Vector4f & viewpoint)
01289 {
01290 pcl::IndicesPtr indices(new std::vector<int>);
01291 return normalFiltering(cloud, indices, angleMax, normal, normalKSearch, viewpoint);
01292 }
01293
01294
01295
01296 pcl::IndicesPtr normalFiltering(
01297 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
01298 const pcl::IndicesPtr & indices,
01299 float angleMax,
01300 const Eigen::Vector4f & normal,
01301 int normalKSearch,
01302 const Eigen::Vector4f & viewpoint)
01303 {
01304 pcl::IndicesPtr output(new std::vector<int>());
01305
01306 if(cloud->size())
01307 {
01308 typedef pcl::search::KdTree<pcl::PointXYZ> KdTree;
01309 typedef KdTree::Ptr KdTreePtr;
01310
01311 pcl::NormalEstimationOMP<pcl::PointXYZ, pcl::Normal> ne;
01312 ne.setInputCloud (cloud);
01313 if(indices->size())
01314 {
01315 ne.setIndices(indices);
01316 }
01317
01318 KdTreePtr tree (new KdTree(false));
01319
01320 if(indices->size())
01321 {
01322 tree->setInputCloud(cloud, indices);
01323 }
01324 else
01325 {
01326 tree->setInputCloud(cloud);
01327 }
01328 ne.setSearchMethod (tree);
01329
01330 pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>);
01331
01332 ne.setKSearch(normalKSearch);
01333 if(viewpoint[0] != 0 || viewpoint[1] != 0 || viewpoint[2] != 0)
01334 {
01335 ne.setViewPoint(viewpoint[0], viewpoint[1], viewpoint[2]);
01336 }
01337
01338 ne.compute (*cloud_normals);
01339
01340 output->resize(cloud_normals->size());
01341 int oi = 0;
01342 for(unsigned int i=0; i<cloud_normals->size(); ++i)
01343 {
01344 Eigen::Vector4f v(cloud_normals->at(i).normal_x, cloud_normals->at(i).normal_y, cloud_normals->at(i).normal_z, 0.0f);
01345 float angle = pcl::getAngle3D(normal, v);
01346 if(angle < angleMax)
01347 {
01348 output->at(oi++) = indices->size()!=0?indices->at(i):i;
01349 }
01350 }
01351 output->resize(oi);
01352 }
01353
01354 return output;
01355 }
01356 pcl::IndicesPtr normalFiltering(
01357 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
01358 const pcl::IndicesPtr & indices,
01359 float angleMax,
01360 const Eigen::Vector4f & normal,
01361 int normalKSearch,
01362 const Eigen::Vector4f & viewpoint)
01363 {
01364 pcl::IndicesPtr output(new std::vector<int>());
01365
01366 if(cloud->size())
01367 {
01368 typedef pcl::search::KdTree<pcl::PointXYZRGB> KdTree;
01369 typedef KdTree::Ptr KdTreePtr;
01370
01371 pcl::NormalEstimationOMP<pcl::PointXYZRGB, pcl::Normal> ne;
01372 ne.setInputCloud (cloud);
01373 if(indices->size())
01374 {
01375 ne.setIndices(indices);
01376 }
01377
01378 KdTreePtr tree (new KdTree(false));
01379
01380 if(indices->size())
01381 {
01382 tree->setInputCloud(cloud, indices);
01383 }
01384 else
01385 {
01386 tree->setInputCloud(cloud);
01387 }
01388 ne.setSearchMethod (tree);
01389
01390 pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>);
01391
01392 ne.setKSearch (normalKSearch);
01393 if(viewpoint[0] != 0 || viewpoint[1] != 0 || viewpoint[2] != 0)
01394 {
01395 ne.setViewPoint(viewpoint[0], viewpoint[1], viewpoint[2]);
01396 }
01397
01398 ne.compute (*cloud_normals);
01399
01400 output->resize(cloud_normals->size());
01401 int oi = 0;
01402 for(unsigned int i=0; i<cloud_normals->size(); ++i)
01403 {
01404 Eigen::Vector4f v(cloud_normals->at(i).normal_x, cloud_normals->at(i).normal_y, cloud_normals->at(i).normal_z, 0.0f);
01405 float angle = pcl::getAngle3D(normal, v);
01406 if(angle < angleMax)
01407 {
01408 output->at(oi++) = indices->size()!=0?indices->at(i):i;
01409 }
01410 }
01411 output->resize(oi);
01412 }
01413
01414 return output;
01415 }
01416 pcl::IndicesPtr normalFiltering(
01417 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
01418 const pcl::IndicesPtr & indices,
01419 float angleMax,
01420 const Eigen::Vector4f & normal,
01421 int normalKSearch,
01422 const Eigen::Vector4f & viewpoint)
01423 {
01424 pcl::IndicesPtr output(new std::vector<int>());
01425
01426 if(cloud->size())
01427 {
01428 int oi = 0;
01429 if(indices->size())
01430 {
01431 output->resize(indices->size());
01432 for(unsigned int i=0; i<indices->size(); ++i)
01433 {
01434 Eigen::Vector4f v(cloud->at(indices->at(i)).normal_x, cloud->at(indices->at(i)).normal_y, cloud->at(indices->at(i)).normal_z, 0.0f);
01435 float angle = pcl::getAngle3D(normal, v);
01436 if(angle < angleMax)
01437 {
01438 output->at(oi++) = indices->size()!=0?indices->at(i):i;
01439 }
01440 }
01441 }
01442 else
01443 {
01444 output->resize(cloud->size());
01445 for(unsigned int i=0; i<cloud->size(); ++i)
01446 {
01447 Eigen::Vector4f v(cloud->at(i).normal_x, cloud->at(i).normal_y, cloud->at(i).normal_z, 0.0f);
01448 float angle = pcl::getAngle3D(normal, v);
01449 if(angle < angleMax)
01450 {
01451 output->at(oi++) = indices->size()!=0?indices->at(i):i;
01452 }
01453 }
01454 }
01455
01456 output->resize(oi);
01457 }
01458
01459 return output;
01460 }
01461
01462 std::vector<pcl::IndicesPtr> extractClusters(
01463 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
01464 float clusterTolerance,
01465 int minClusterSize,
01466 int maxClusterSize,
01467 int * biggestClusterIndex)
01468 {
01469 pcl::IndicesPtr indices(new std::vector<int>);
01470 return extractClusters(cloud, indices, clusterTolerance, minClusterSize, maxClusterSize, biggestClusterIndex);
01471 }
01472 std::vector<pcl::IndicesPtr> extractClusters(
01473 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
01474 float clusterTolerance,
01475 int minClusterSize,
01476 int maxClusterSize,
01477 int * biggestClusterIndex)
01478 {
01479 pcl::IndicesPtr indices(new std::vector<int>);
01480 return extractClusters(cloud, indices, clusterTolerance, minClusterSize, maxClusterSize, biggestClusterIndex);
01481 }
01482
01483 std::vector<pcl::IndicesPtr> extractClusters(
01484 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
01485 const pcl::IndicesPtr & indices,
01486 float clusterTolerance,
01487 int minClusterSize,
01488 int maxClusterSize,
01489 int * biggestClusterIndex)
01490 {
01491 typedef pcl::search::KdTree<pcl::PointXYZ> KdTree;
01492 typedef KdTree::Ptr KdTreePtr;
01493
01494 KdTreePtr tree(new KdTree);
01495 pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;
01496 ec.setClusterTolerance (clusterTolerance);
01497 ec.setMinClusterSize (minClusterSize);
01498 ec.setMaxClusterSize (maxClusterSize);
01499 ec.setInputCloud (cloud);
01500
01501 if(indices->size())
01502 {
01503 ec.setIndices(indices);
01504 tree->setInputCloud(cloud, indices);
01505 }
01506 else
01507 {
01508 tree->setInputCloud(cloud);
01509 }
01510 ec.setSearchMethod (tree);
01511
01512 std::vector<pcl::PointIndices> cluster_indices;
01513 ec.extract (cluster_indices);
01514
01515 int maxIndex=-1;
01516 unsigned int maxSize = 0;
01517 std::vector<pcl::IndicesPtr> output(cluster_indices.size());
01518 for(unsigned int i=0; i<cluster_indices.size(); ++i)
01519 {
01520 output[i] = pcl::IndicesPtr(new std::vector<int>(cluster_indices[i].indices));
01521
01522 if(maxSize < cluster_indices[i].indices.size())
01523 {
01524 maxSize = (unsigned int)cluster_indices[i].indices.size();
01525 maxIndex = i;
01526 }
01527 }
01528 if(biggestClusterIndex)
01529 {
01530 *biggestClusterIndex = maxIndex;
01531 }
01532
01533 return output;
01534 }
01535 std::vector<pcl::IndicesPtr> extractClusters(
01536 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
01537 const pcl::IndicesPtr & indices,
01538 float clusterTolerance,
01539 int minClusterSize,
01540 int maxClusterSize,
01541 int * biggestClusterIndex)
01542 {
01543 typedef pcl::search::KdTree<pcl::PointXYZRGB> KdTree;
01544 typedef KdTree::Ptr KdTreePtr;
01545
01546 KdTreePtr tree(new KdTree);
01547 pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> ec;
01548 ec.setClusterTolerance (clusterTolerance);
01549 ec.setMinClusterSize (minClusterSize);
01550 ec.setMaxClusterSize (maxClusterSize);
01551 ec.setInputCloud (cloud);
01552
01553 if(indices->size())
01554 {
01555 ec.setIndices(indices);
01556 tree->setInputCloud(cloud, indices);
01557 }
01558 else
01559 {
01560 tree->setInputCloud(cloud);
01561 }
01562 ec.setSearchMethod (tree);
01563
01564 std::vector<pcl::PointIndices> cluster_indices;
01565 ec.extract (cluster_indices);
01566
01567 int maxIndex=-1;
01568 unsigned int maxSize = 0;
01569 std::vector<pcl::IndicesPtr> output(cluster_indices.size());
01570 for(unsigned int i=0; i<cluster_indices.size(); ++i)
01571 {
01572 output[i] = pcl::IndicesPtr(new std::vector<int>(cluster_indices[i].indices));
01573
01574 if(maxSize < cluster_indices[i].indices.size())
01575 {
01576 maxSize = (unsigned int)cluster_indices[i].indices.size();
01577 maxIndex = i;
01578 }
01579 }
01580 if(biggestClusterIndex)
01581 {
01582 *biggestClusterIndex = maxIndex;
01583 }
01584
01585 return output;
01586 }
01587 std::vector<pcl::IndicesPtr> extractClusters(
01588 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
01589 const pcl::IndicesPtr & indices,
01590 float clusterTolerance,
01591 int minClusterSize,
01592 int maxClusterSize,
01593 int * biggestClusterIndex)
01594 {
01595 typedef pcl::search::KdTree<pcl::PointXYZRGBNormal> KdTree;
01596 typedef KdTree::Ptr KdTreePtr;
01597
01598 KdTreePtr tree(new KdTree);
01599 pcl::EuclideanClusterExtraction<pcl::PointXYZRGBNormal> ec;
01600 ec.setClusterTolerance (clusterTolerance);
01601 ec.setMinClusterSize (minClusterSize);
01602 ec.setMaxClusterSize (maxClusterSize);
01603 ec.setInputCloud (cloud);
01604
01605 if(indices->size())
01606 {
01607 ec.setIndices(indices);
01608 tree->setInputCloud(cloud, indices);
01609 }
01610 else
01611 {
01612 tree->setInputCloud(cloud);
01613 }
01614 ec.setSearchMethod (tree);
01615
01616 std::vector<pcl::PointIndices> cluster_indices;
01617 ec.extract (cluster_indices);
01618
01619 int maxIndex=-1;
01620 unsigned int maxSize = 0;
01621 std::vector<pcl::IndicesPtr> output(cluster_indices.size());
01622 for(unsigned int i=0; i<cluster_indices.size(); ++i)
01623 {
01624 output[i] = pcl::IndicesPtr(new std::vector<int>(cluster_indices[i].indices));
01625
01626 if(maxSize < cluster_indices[i].indices.size())
01627 {
01628 maxSize = (unsigned int)cluster_indices[i].indices.size();
01629 maxIndex = i;
01630 }
01631 }
01632 if(biggestClusterIndex)
01633 {
01634 *biggestClusterIndex = maxIndex;
01635 }
01636
01637 return output;
01638 }
01639
01640 pcl::IndicesPtr extractIndices(
01641 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
01642 const pcl::IndicesPtr & indices,
01643 bool negative)
01644 {
01645 pcl::IndicesPtr output(new std::vector<int>);
01646 pcl::ExtractIndices<pcl::PointXYZ> extract;
01647 extract.setInputCloud (cloud);
01648 extract.setIndices(indices);
01649 extract.setNegative(negative);
01650 extract.filter(*output);
01651 return output;
01652 }
01653 pcl::IndicesPtr extractIndices(
01654 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
01655 const pcl::IndicesPtr & indices,
01656 bool negative)
01657 {
01658 pcl::IndicesPtr output(new std::vector<int>);
01659 pcl::ExtractIndices<pcl::PointXYZRGB> extract;
01660 extract.setInputCloud (cloud);
01661 extract.setIndices(indices);
01662 extract.setNegative(negative);
01663 extract.filter(*output);
01664 return output;
01665 }
01666 pcl::IndicesPtr extractIndices(
01667 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
01668 const pcl::IndicesPtr & indices,
01669 bool negative)
01670 {
01671 pcl::IndicesPtr output(new std::vector<int>);
01672 pcl::ExtractIndices<pcl::PointXYZRGBNormal> extract;
01673 extract.setInputCloud (cloud);
01674 extract.setIndices(indices);
01675 extract.setNegative(negative);
01676 extract.filter(*output);
01677 return output;
01678 }
01679
01680 pcl::PointCloud<pcl::PointXYZ>::Ptr extractIndices(
01681 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
01682 const pcl::IndicesPtr & indices,
01683 bool negative,
01684 bool keepOrganized)
01685 {
01686 pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
01687 pcl::ExtractIndices<pcl::PointXYZ> extract;
01688 extract.setInputCloud (cloud);
01689 extract.setIndices(indices);
01690 extract.setNegative(negative);
01691 extract.setKeepOrganized(keepOrganized);
01692 extract.filter(*output);
01693 return output;
01694 }
01695 pcl::PointCloud<pcl::PointXYZRGB>::Ptr extractIndices(
01696 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
01697 const pcl::IndicesPtr & indices,
01698 bool negative,
01699 bool keepOrganized)
01700 {
01701 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGB>);
01702 pcl::ExtractIndices<pcl::PointXYZRGB> extract;
01703 extract.setInputCloud (cloud);
01704 extract.setIndices(indices);
01705 extract.setNegative(negative);
01706 extract.setKeepOrganized(keepOrganized);
01707 extract.filter(*output);
01708 return output;
01709 }
01710 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr extractIndices(
01711 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
01712 const pcl::IndicesPtr & indices,
01713 bool negative,
01714 bool keepOrganized)
01715 {
01716 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
01717 pcl::ExtractIndices<pcl::PointXYZRGBNormal> extract;
01718 extract.setInputCloud (cloud);
01719 extract.setIndices(indices);
01720 extract.setNegative(negative);
01721 extract.setKeepOrganized(keepOrganized);
01722 extract.filter(*output);
01723 return output;
01724 }
01725
01726 pcl::IndicesPtr extractPlane(
01727 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
01728 float distanceThreshold,
01729 int maxIterations,
01730 pcl::ModelCoefficients * coefficientsOut)
01731 {
01732 pcl::IndicesPtr indices(new std::vector<int>);
01733 return extractPlane(cloud, indices, distanceThreshold, maxIterations, coefficientsOut);
01734 }
01735
01736 pcl::IndicesPtr extractPlane(
01737 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
01738 const pcl::IndicesPtr & indices,
01739 float distanceThreshold,
01740 int maxIterations,
01741 pcl::ModelCoefficients * coefficientsOut)
01742 {
01743
01744 pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
01745 pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
01746
01747 pcl::SACSegmentation<pcl::PointXYZ> seg;
01748
01749 seg.setOptimizeCoefficients (true);
01750 seg.setMaxIterations (maxIterations);
01751
01752 seg.setModelType (pcl::SACMODEL_PLANE);
01753 seg.setMethodType (pcl::SAC_RANSAC);
01754 seg.setDistanceThreshold (distanceThreshold);
01755
01756 seg.setInputCloud (cloud);
01757 if(indices->size())
01758 {
01759 seg.setIndices(indices);
01760 }
01761 seg.segment (*inliers, *coefficients);
01762
01763 if(coefficientsOut)
01764 {
01765 *coefficientsOut = *coefficients;
01766 }
01767
01768 return pcl::IndicesPtr(new std::vector<int>(inliers->indices));
01769 }
01770
01771 }
01772
01773 }