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 #ifndef UTIL3D_FILTERING_H_
00029 #define UTIL3D_FILTERING_H_
00030
00031 #include <rtabmap/core/RtabmapExp.h>
00032 #include <rtabmap/core/Transform.h>
00033
00034 #include <pcl/point_cloud.h>
00035 #include <pcl/point_types.h>
00036 #include <pcl/pcl_base.h>
00037 #include <pcl/ModelCoefficients.h>
00038
00039 namespace rtabmap
00040 {
00041
00042 namespace util3d
00043 {
00044
00045 cv::Mat RTABMAP_EXP downsample(
00046 const cv::Mat & cloud,
00047 int step);
00048 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP downsample(
00049 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00050 int step);
00051 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP downsample(
00052 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00053 int step);
00054
00055 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP voxelize(
00056 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00057 const pcl::IndicesPtr & indices,
00058 float voxelSize);
00059 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP voxelize(
00060 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00061 const pcl::IndicesPtr & indices,
00062 float voxelSize);
00063 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP voxelize(
00064 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00065 const pcl::IndicesPtr & indices,
00066 float voxelSize);
00067 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP voxelize(
00068 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00069 const pcl::IndicesPtr & indices,
00070 float voxelSize);
00071 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP voxelize(
00072 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00073 float voxelSize);
00074 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP voxelize(
00075 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00076 float voxelSize);
00077 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP voxelize(
00078 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00079 float voxelSize);
00080 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP voxelize(
00081 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00082 float voxelSize);
00083
00084 inline pcl::PointCloud<pcl::PointXYZ>::Ptr uniformSampling(
00085 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00086 float voxelSize)
00087 {
00088 return voxelize(cloud, voxelSize);
00089 }
00090 inline pcl::PointCloud<pcl::PointXYZRGB>::Ptr uniformSampling(
00091 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00092 float voxelSize)
00093 {
00094 return voxelize(cloud, voxelSize);
00095 }
00096 inline pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr uniformSampling(
00097 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00098 float voxelSize)
00099 {
00100 return voxelize(cloud, voxelSize);
00101 }
00102
00103
00104 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP randomSampling(
00105 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00106 int samples);
00107 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP randomSampling(
00108 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00109 int samples);
00110
00111
00112 pcl::IndicesPtr RTABMAP_EXP passThrough(
00113 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00114 const pcl::IndicesPtr & indices,
00115 const std::string & axis,
00116 float min,
00117 float max,
00118 bool negative = false);
00119 pcl::IndicesPtr RTABMAP_EXP passThrough(
00120 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00121 const pcl::IndicesPtr & indices,
00122 const std::string & axis,
00123 float min,
00124 float max,
00125 bool negative = false);
00126 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP passThrough(
00127 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00128 const std::string & axis,
00129 float min,
00130 float max,
00131 bool negative = false);
00132 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP passThrough(
00133 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00134 const std::string & axis,
00135 float min,
00136 float max,
00137 bool negative = false);
00138
00139
00140 pcl::IndicesPtr RTABMAP_EXP frustumFiltering(
00141 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00142 const pcl::IndicesPtr & indices,
00143 const Transform & cameraPose,
00144 float horizontalFOV,
00145 float verticalFOV,
00146 float nearClipPlaneDistance,
00147 float farClipPlaneDistance,
00148 bool negative = false);
00149
00150 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP frustumFiltering(
00151 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00152 const Transform & cameraPose,
00153 float horizontalFOV,
00154 float verticalFOV,
00155 float nearClipPlaneDistance,
00156 float farClipPlaneDistance,
00157 bool negative = false);
00158
00159 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP frustumFiltering(
00160 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00161 const Transform & cameraPose,
00162 float horizontalFOV,
00163 float verticalFOV,
00164 float nearClipPlaneDistance,
00165 float farClipPlaneDistance,
00166 bool negative = false);
00167
00168
00169 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP removeNaNFromPointCloud(
00170 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
00171 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP removeNaNFromPointCloud(
00172 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud);
00173
00174
00175 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(
00176 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
00177 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(
00178 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
00179
00184 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00185 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00186 float radiusSearch,
00187 int minNeighborsInRadius);
00188 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00189 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00190 float radiusSearch,
00191 int minNeighborsInRadius);
00192 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00193 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00194 float radiusSearch,
00195 int minNeighborsInRadius);
00196 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00197 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00198 float radiusSearch,
00199 int minNeighborsInRadius);
00200
00213 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00214 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00215 const pcl::IndicesPtr & indices,
00216 float radiusSearch,
00217 int minNeighborsInRadius);
00218 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00219 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00220 const pcl::IndicesPtr & indices,
00221 float radiusSearch,
00222 int minNeighborsInRadius);
00223 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00224 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00225 const pcl::IndicesPtr & indices,
00226 float radiusSearch,
00227 int minNeighborsInRadius);
00228 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00229 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00230 const pcl::IndicesPtr & indices,
00231 float radiusSearch,
00232 int minNeighborsInRadius);
00233
00237 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP subtractFiltering(
00238 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00239 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
00240 float radiusSearch,
00241 int minNeighborsInRadius = 1);
00242
00252 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
00253 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00254 const pcl::IndicesPtr & indices,
00255 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
00256 const pcl::IndicesPtr & substractIndices,
00257 float radiusSearch,
00258 int minNeighborsInRadius = 1);
00259
00263 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP subtractFiltering(
00264 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00265 const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
00266 float radiusSearch,
00267 float maxAngle = M_PI/4.0f,
00268 int minNeighborsInRadius = 1);
00269
00279 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
00280 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00281 const pcl::IndicesPtr & indices,
00282 const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
00283 const pcl::IndicesPtr & substractIndices,
00284 float radiusSearch,
00285 float maxAngle = M_PI/4.0f,
00286 int minNeighborsInRadius = 1);
00287
00291 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP subtractFiltering(
00292 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00293 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
00294 float radiusSearch,
00295 float maxAngle = M_PI/4.0f,
00296 int minNeighborsInRadius = 1);
00297
00307 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
00308 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00309 const pcl::IndicesPtr & indices,
00310 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
00311 const pcl::IndicesPtr & substractIndices,
00312 float radiusSearch,
00313 float maxAngle = M_PI/4.0f,
00314 int minNeighborsInRadius = 1);
00315
00325 pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(
00326 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00327 const pcl::IndicesPtr & indices,
00328 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
00329 const pcl::IndicesPtr & substractIndices,
00330 float radiusSearchRatio = 0.01,
00331 int minNeighborsInRadius = 1,
00332 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
00333
00343 pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(
00344 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00345 const pcl::IndicesPtr & indices,
00346 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
00347 const pcl::IndicesPtr & substractIndices,
00348 float radiusSearchRatio = 0.01,
00349 float maxAngle = M_PI/4.0f,
00350 int minNeighborsInRadius = 1,
00351 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
00352
00353
00358 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
00359 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00360 float angleMax,
00361 const Eigen::Vector4f & normal,
00362 int normalKSearch,
00363 const Eigen::Vector4f & viewpoint);
00364 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
00365 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00366 float angleMax,
00367 const Eigen::Vector4f & normal,
00368 int normalKSearch,
00369 const Eigen::Vector4f & viewpoint);
00370
00388 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
00389 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00390 const pcl::IndicesPtr & indices,
00391 float angleMax,
00392 const Eigen::Vector4f & normal,
00393 int normalKSearch,
00394 const Eigen::Vector4f & viewpoint);
00395 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
00396 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00397 const pcl::IndicesPtr & indices,
00398 float angleMax,
00399 const Eigen::Vector4f & normal,
00400 int normalKSearch,
00401 const Eigen::Vector4f & viewpoint);
00402 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
00403 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00404 const pcl::IndicesPtr & indices,
00405 float angleMax,
00406 const Eigen::Vector4f & normal,
00407 int normalKSearch,
00408 const Eigen::Vector4f & viewpoint);
00409
00413 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
00414 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00415 float clusterTolerance,
00416 int minClusterSize,
00417 int maxClusterSize = std::numeric_limits<int>::max(),
00418 int * biggestClusterIndex = 0);
00419 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
00420 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00421 float clusterTolerance,
00422 int minClusterSize,
00423 int maxClusterSize = std::numeric_limits<int>::max(),
00424 int * biggestClusterIndex = 0);
00425
00438 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
00439 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00440 const pcl::IndicesPtr & indices,
00441 float clusterTolerance,
00442 int minClusterSize,
00443 int maxClusterSize = std::numeric_limits<int>::max(),
00444 int * biggestClusterIndex = 0);
00445 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
00446 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00447 const pcl::IndicesPtr & indices,
00448 float clusterTolerance,
00449 int minClusterSize,
00450 int maxClusterSize = std::numeric_limits<int>::max(),
00451 int * biggestClusterIndex = 0);
00452 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
00453 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00454 const pcl::IndicesPtr & indices,
00455 float clusterTolerance,
00456 int minClusterSize,
00457 int maxClusterSize = std::numeric_limits<int>::max(),
00458 int * biggestClusterIndex = 0);
00459
00460 pcl::IndicesPtr RTABMAP_EXP extractIndices(
00461 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00462 const pcl::IndicesPtr & indices,
00463 bool negative);
00464 pcl::IndicesPtr RTABMAP_EXP extractIndices(
00465 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00466 const pcl::IndicesPtr & indices,
00467 bool negative);
00468 pcl::IndicesPtr RTABMAP_EXP extractIndices(
00469 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00470 const pcl::IndicesPtr & indices,
00471 bool negative);
00472
00473 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP extractIndices(
00474 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00475 const pcl::IndicesPtr & indices,
00476 bool negative,
00477 bool keepOrganized);
00478 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP extractIndices(
00479 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00480 const pcl::IndicesPtr & indices,
00481 bool negative,
00482 bool keepOrganized);
00483 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP extractIndices(
00484 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00485 const pcl::IndicesPtr & indices,
00486 bool negative,
00487 bool keepOrganized);
00488
00489 pcl::IndicesPtr extractPlane(
00490 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00491 float distanceThreshold,
00492 int maxIterations = 100,
00493 pcl::ModelCoefficients * coefficientsOut = 0);
00494 pcl::IndicesPtr extractPlane(
00495 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00496 const pcl::IndicesPtr & indices,
00497 float distanceThreshold,
00498 int maxIterations = 100,
00499 pcl::ModelCoefficients * coefficientsOut = 0);
00500
00501 }
00502 }
00503
00504 #endif