util3d_filtering.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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 #include <pcl/point_cloud.h>
00034 #include <pcl/point_types.h>
00035 #include <pcl/pcl_base.h>
00036 #include <pcl/ModelCoefficients.h>
00037 #include <rtabmap/core/LaserScan.h>
00038 
00039 namespace rtabmap
00040 {
00041 
00042 namespace util3d
00043 {
00044 
00051 LaserScan RTABMAP_EXP commonFiltering(
00052                 const LaserScan & scan,
00053                 int downsamplingStep,
00054                 float rangeMin = 0.0f,
00055                 float rangeMax = 0.0f,
00056                 float voxelSize = 0.0f,
00057                 int normalK = 0,
00058                 float normalRadius = 0.0f,
00059                 bool forceGroundNormalsUp = false);
00060 
00061 LaserScan RTABMAP_EXP rangeFiltering(
00062                 const LaserScan & scan,
00063                 float rangeMin,
00064                 float rangeMax);
00065 
00066 LaserScan RTABMAP_EXP downsample(
00067                 const LaserScan & cloud,
00068                 int step);
00069 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP downsample(
00070                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00071                 int step);
00072 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP downsample(
00073                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00074                 int step);
00075 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP downsample(
00076                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00077                 int step);
00078 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP downsample(
00079                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00080                 int step);
00081 
00082 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP voxelize(
00083                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00084                 const pcl::IndicesPtr & indices,
00085                 float voxelSize);
00086 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP voxelize(
00087                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00088                 const pcl::IndicesPtr & indices,
00089                 float voxelSize);
00090 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP voxelize(
00091                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00092                 const pcl::IndicesPtr & indices,
00093                 float voxelSize);
00094 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP voxelize(
00095                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00096                 const pcl::IndicesPtr & indices,
00097                 float voxelSize);
00098 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP voxelize(
00099                 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
00100                 const pcl::IndicesPtr & indices,
00101                 float voxelSize);
00102 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP voxelize(
00103                 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
00104                 const pcl::IndicesPtr & indices,
00105                 float voxelSize);
00106 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP voxelize(
00107                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00108                 float voxelSize);
00109 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP voxelize(
00110                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00111                 float voxelSize);
00112 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP voxelize(
00113                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00114                 float voxelSize);
00115 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP voxelize(
00116                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00117                 float voxelSize);
00118 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP voxelize(
00119                 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
00120                 float voxelSize);
00121 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP voxelize(
00122                 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
00123                 float voxelSize);
00124 
00125 inline pcl::PointCloud<pcl::PointXYZ>::Ptr uniformSampling(
00126                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00127                 float voxelSize)
00128 {
00129         return voxelize(cloud, voxelSize);
00130 }
00131 inline pcl::PointCloud<pcl::PointXYZRGB>::Ptr uniformSampling(
00132                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00133                 float voxelSize)
00134 {
00135         return voxelize(cloud, voxelSize);
00136 }
00137 inline pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr uniformSampling(
00138                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00139                 float voxelSize)
00140 {
00141         return voxelize(cloud, voxelSize);
00142 }
00143 
00144 
00145 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP randomSampling(
00146                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00147                 int samples);
00148 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP randomSampling(
00149                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00150                 int samples);
00151 
00152 
00153 pcl::IndicesPtr RTABMAP_EXP passThrough(
00154                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00155                 const pcl::IndicesPtr & indices,
00156                 const std::string & axis,
00157                 float min,
00158                 float max,
00159                 bool negative = false);
00160 pcl::IndicesPtr RTABMAP_EXP passThrough(
00161                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00162                 const pcl::IndicesPtr & indices,
00163                 const std::string & axis,
00164                 float min,
00165                 float max,
00166                 bool negative = false);
00167 pcl::IndicesPtr RTABMAP_EXP passThrough(
00168                 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
00169                 const pcl::IndicesPtr & indices,
00170                 const std::string & axis,
00171                 float min,
00172                 float max,
00173                 bool negative = false);
00174 pcl::IndicesPtr RTABMAP_EXP passThrough(
00175                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00176                 const pcl::IndicesPtr & indices,
00177                 const std::string & axis,
00178                 float min,
00179                 float max,
00180                 bool negative = false);
00181 pcl::IndicesPtr RTABMAP_EXP passThrough(
00182                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00183                 const pcl::IndicesPtr & indices,
00184                 const std::string & axis,
00185                 float min,
00186                 float max,
00187                 bool negative = false);
00188 pcl::IndicesPtr RTABMAP_EXP passThrough(
00189                 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
00190                 const pcl::IndicesPtr & indices,
00191                 const std::string & axis,
00192                 float min,
00193                 float max,
00194                 bool negative = false);
00195 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP passThrough(
00196                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00197                 const std::string & axis,
00198                 float min,
00199                 float max,
00200                 bool negative = false);
00201 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP passThrough(
00202                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00203                 const std::string & axis,
00204                 float min,
00205                 float max,
00206                 bool negative = false);
00207 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP passThrough(
00208                 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
00209                 const std::string & axis,
00210                 float min,
00211                 float max,
00212                 bool negative = false);
00213 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP passThrough(
00214                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00215                 const std::string & axis,
00216                 float min,
00217                 float max,
00218                 bool negative = false);
00219 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP passThrough(
00220                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00221                 const std::string & axis,
00222                 float min,
00223                 float max,
00224                 bool negative = false);
00225 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP passThrough(
00226                 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
00227                 const std::string & axis,
00228                 float min,
00229                 float max,
00230                 bool negative = false);
00231 
00232 pcl::IndicesPtr RTABMAP_EXP cropBox(
00233                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00234                 const pcl::IndicesPtr & indices,
00235                 const Eigen::Vector4f & min,
00236                 const Eigen::Vector4f & max,
00237                 const Transform & transform = Transform::getIdentity(),
00238                 bool negative = false);
00239 pcl::IndicesPtr RTABMAP_EXP cropBox(
00240                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00241                 const pcl::IndicesPtr & indices,
00242                 const Eigen::Vector4f & min,
00243                 const Eigen::Vector4f & max,
00244                 const Transform & transform = Transform::getIdentity(),
00245                 bool negative = false);
00246 pcl::IndicesPtr RTABMAP_EXP cropBox(
00247                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00248                 const pcl::IndicesPtr & indices,
00249                 const Eigen::Vector4f & min,
00250                 const Eigen::Vector4f & max,
00251                 const Transform & transform = Transform::getIdentity(),
00252                 bool negative = false);
00253 pcl::IndicesPtr RTABMAP_EXP cropBox(
00254                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00255                 const pcl::IndicesPtr & indices,
00256                 const Eigen::Vector4f & min,
00257                 const Eigen::Vector4f & max,
00258                 const Transform & transform = Transform::getIdentity(),
00259                 bool negative = false);
00260 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cropBox(
00261                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00262                 const Eigen::Vector4f & min,
00263                 const Eigen::Vector4f & max,
00264                 const Transform & transform = Transform::getIdentity(),
00265                 bool negative = false);
00266 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP cropBox(
00267                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00268                 const Eigen::Vector4f & min,
00269                 const Eigen::Vector4f & max,
00270                 const Transform & transform = Transform::getIdentity(),
00271                 bool negative = false);
00272 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cropBox(
00273                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00274                 const Eigen::Vector4f & min,
00275                 const Eigen::Vector4f & max,
00276                 const Transform & transform = Transform::getIdentity(),
00277                 bool negative = false);
00278 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP cropBox(
00279                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00280                 const Eigen::Vector4f & min,
00281                 const Eigen::Vector4f & max,
00282                 const Transform & transform = Transform::getIdentity(),
00283                 bool negative = false);
00284 
00285 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
00286 pcl::IndicesPtr RTABMAP_EXP frustumFiltering(
00287                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00288                 const pcl::IndicesPtr & indices,
00289                 const Transform & cameraPose,
00290                 float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
00291                 float verticalFOV,   // in degrees, yfov = atan((image_height/2)/fy)*2
00292                 float nearClipPlaneDistance,
00293                 float farClipPlaneDistance,
00294                 bool negative = false);
00295 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
00296 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP frustumFiltering(
00297                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00298                 const Transform & cameraPose,
00299                 float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
00300                 float verticalFOV,   // in degrees, yfov = atan((image_height/2)/fy)*2
00301                 float nearClipPlaneDistance,
00302                 float farClipPlaneDistance,
00303                 bool negative = false);
00304 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
00305 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP frustumFiltering(
00306                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00307                 const Transform & cameraPose,
00308                 float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
00309                 float verticalFOV,   // in degrees, yfov = atan((image_height/2)/fy)*2
00310                 float nearClipPlaneDistance,
00311                 float farClipPlaneDistance,
00312                 bool negative = false);
00313 
00314 
00315 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP removeNaNFromPointCloud(
00316                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
00317 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP removeNaNFromPointCloud(
00318                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud);
00319 
00320 
00321 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(
00322                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
00323 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(
00324                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
00325 
00330 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00331                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00332                 float radiusSearch,
00333                 int minNeighborsInRadius);
00334 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00335                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00336                 float radiusSearch,
00337                 int minNeighborsInRadius);
00338 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00339                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00340                 float radiusSearch,
00341                 int minNeighborsInRadius);
00342 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00343                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00344                 float radiusSearch,
00345                 int minNeighborsInRadius);
00346 
00359 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00360                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00361                 const pcl::IndicesPtr & indices,
00362                 float radiusSearch,
00363                 int minNeighborsInRadius);
00364 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00365                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00366                 const pcl::IndicesPtr & indices,
00367                 float radiusSearch,
00368                 int minNeighborsInRadius);
00369 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00370                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00371                 const pcl::IndicesPtr & indices,
00372                 float radiusSearch,
00373                 int minNeighborsInRadius);
00374 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
00375                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00376                 const pcl::IndicesPtr & indices,
00377                 float radiusSearch,
00378                 int minNeighborsInRadius);
00379 
00383 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP subtractFiltering(
00384                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00385                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
00386                 float radiusSearch,
00387                 int minNeighborsInRadius = 1);
00388 
00398 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
00399                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00400                 const pcl::IndicesPtr & indices,
00401                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
00402                 const pcl::IndicesPtr & substractIndices,
00403                 float radiusSearch,
00404                 int minNeighborsInRadius = 1);
00405 
00409 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP subtractFiltering(
00410                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00411                 const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
00412                 float radiusSearch,
00413                 float maxAngle = M_PI/4.0f,
00414                 int minNeighborsInRadius = 1);
00415 
00425 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
00426                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00427                 const pcl::IndicesPtr & indices,
00428                 const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
00429                 const pcl::IndicesPtr & substractIndices,
00430                 float radiusSearch,
00431                 float maxAngle = M_PI/4.0f,
00432                 int minNeighborsInRadius = 1);
00433 
00437 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP subtractFiltering(
00438                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00439                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
00440                 float radiusSearch,
00441                 float maxAngle = M_PI/4.0f,
00442                 int minNeighborsInRadius = 1);
00443 
00453 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
00454                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00455                 const pcl::IndicesPtr & indices,
00456                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
00457                 const pcl::IndicesPtr & substractIndices,
00458                 float radiusSearch,
00459                 float maxAngle = M_PI/4.0f,
00460                 int minNeighborsInRadius = 1);
00461 
00471 pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(
00472                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00473                 const pcl::IndicesPtr & indices,
00474                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
00475                 const pcl::IndicesPtr & substractIndices,
00476                 float radiusSearchRatio = 0.01,
00477                 int minNeighborsInRadius = 1,
00478                 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
00479 
00489 pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(
00490                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00491                 const pcl::IndicesPtr & indices,
00492                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
00493                 const pcl::IndicesPtr & substractIndices,
00494                 float radiusSearchRatio = 0.01,
00495                 float maxAngle = M_PI/4.0f,
00496                 int minNeighborsInRadius = 1,
00497                 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
00498 
00499 
00504 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
00505                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00506                 float angleMax,
00507                 const Eigen::Vector4f & normal,
00508                 int normalKSearch,
00509                 const Eigen::Vector4f & viewpoint);
00510 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
00511                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00512                 float angleMax,
00513                 const Eigen::Vector4f & normal,
00514                 int normalKSearch,
00515                 const Eigen::Vector4f & viewpoint);
00516 
00533 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
00534                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00535                 const pcl::IndicesPtr & indices,
00536                 float angleMax,
00537                 const Eigen::Vector4f & normal,
00538                 int normalKSearch,
00539                 const Eigen::Vector4f & viewpoint);
00540 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
00541                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00542                 const pcl::IndicesPtr & indices,
00543                 float angleMax,
00544                 const Eigen::Vector4f & normal,
00545                 int normalKSearch,
00546                 const Eigen::Vector4f & viewpoint);
00547 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
00548                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00549                 const pcl::IndicesPtr & indices,
00550                 float angleMax,
00551                 const Eigen::Vector4f & normal,
00552                 int normalKSearch,
00553                 const Eigen::Vector4f & viewpoint);
00554 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
00555                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00556                 const pcl::IndicesPtr & indices,
00557                 float angleMax,
00558                 const Eigen::Vector4f & normal,
00559                 int normalKSearch,
00560                 const Eigen::Vector4f & viewpoint);
00561 
00565 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
00566                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00567                 float clusterTolerance,
00568                 int minClusterSize,
00569                 int maxClusterSize = std::numeric_limits<int>::max(),
00570                 int * biggestClusterIndex = 0);
00571 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
00572                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00573                 float clusterTolerance,
00574                 int minClusterSize,
00575                 int maxClusterSize = std::numeric_limits<int>::max(),
00576                 int * biggestClusterIndex = 0);
00577 
00590 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
00591                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00592                 const pcl::IndicesPtr & indices,
00593                 float clusterTolerance,
00594                 int minClusterSize,
00595                 int maxClusterSize = std::numeric_limits<int>::max(),
00596                 int * biggestClusterIndex = 0);
00597 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
00598                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00599                 const pcl::IndicesPtr & indices,
00600                 float clusterTolerance,
00601                 int minClusterSize,
00602                 int maxClusterSize = std::numeric_limits<int>::max(),
00603                 int * biggestClusterIndex = 0);
00604 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
00605                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00606                 const pcl::IndicesPtr & indices,
00607                 float clusterTolerance,
00608                 int minClusterSize,
00609                 int maxClusterSize = std::numeric_limits<int>::max(),
00610                 int * biggestClusterIndex = 0);
00611 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
00612                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00613                 const pcl::IndicesPtr & indices,
00614                 float clusterTolerance,
00615                 int minClusterSize,
00616                 int maxClusterSize = std::numeric_limits<int>::max(),
00617                 int * biggestClusterIndex = 0);
00618 
00619 pcl::IndicesPtr RTABMAP_EXP extractIndices(
00620                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00621                 const pcl::IndicesPtr & indices,
00622                 bool negative);
00623 pcl::IndicesPtr RTABMAP_EXP extractIndices(
00624                 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00625                 const pcl::IndicesPtr & indices,
00626                 bool negative);
00627 pcl::IndicesPtr RTABMAP_EXP extractIndices(
00628                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00629                 const pcl::IndicesPtr & indices,
00630                 bool negative);
00631 pcl::IndicesPtr RTABMAP_EXP extractIndices(
00632                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00633                 const pcl::IndicesPtr & indices,
00634                 bool negative);
00635 
00636 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP extractIndices(
00637                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00638                 const pcl::IndicesPtr & indices,
00639                 bool negative,
00640                 bool keepOrganized);
00641 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP extractIndices(
00642                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00643                 const pcl::IndicesPtr & indices,
00644                 bool negative,
00645                 bool keepOrganized);
00646 // PCL default lacks of pcl::PointNormal type support
00647 //pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP extractIndices(
00648 //              const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00649 //              const pcl::IndicesPtr & indices,
00650 //              bool negative,
00651 //              bool keepOrganized);
00652 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP extractIndices(
00653                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00654                 const pcl::IndicesPtr & indices,
00655                 bool negative,
00656                 bool keepOrganized);
00657 
00658 pcl::IndicesPtr extractPlane(
00659                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00660                 float distanceThreshold,
00661                 int maxIterations = 100,
00662                 pcl::ModelCoefficients * coefficientsOut = 0);
00663 pcl::IndicesPtr extractPlane(
00664                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00665                 const pcl::IndicesPtr & indices,
00666                 float distanceThreshold,
00667                 int maxIterations = 100,
00668                 pcl::ModelCoefficients * coefficientsOut = 0);
00669 
00670 } // namespace util3d
00671 } // namespace rtabmap
00672 
00673 #endif /* UTIL3D_FILTERING_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:32