util3d_surface.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_SURFACE_H_
00029 #define UTIL3D_SURFACE_H_
00030 
00031 #include <rtabmap/core/RtabmapExp.h>
00032 
00033 #include <pcl/PolygonMesh.h>
00034 #include <pcl/point_cloud.h>
00035 #include <pcl/point_types.h>
00036 #include <pcl/TextureMesh.h>
00037 #include <pcl/pcl_base.h>
00038 #include <rtabmap/core/Transform.h>
00039 #include <rtabmap/core/CameraModel.h>
00040 #include <rtabmap/core/ProgressState.h>
00041 #include <rtabmap/core/LaserScan.h>
00042 #include <set>
00043 #include <list>
00044 
00045 namespace rtabmap
00046 {
00047 
00048 class Memory;
00049 class DBDriver;
00050 
00051 namespace util3d
00052 {
00053 
00063 void RTABMAP_EXP createPolygonIndexes(
00064                 const std::vector<pcl::Vertices> & polygons,
00065                 int cloudSize,
00066                 std::vector<std::set<int> > & neighborPolygons,
00067                 std::vector<std::set<int> > & vertexPolygons);
00068 
00069 std::list<std::list<int> > RTABMAP_EXP clusterPolygons(
00070                 const std::vector<std::set<int> > & neighborPolygons,
00071                 int minClusterSize = 0);
00072 
00073 std::vector<pcl::Vertices> RTABMAP_EXP organizedFastMesh(
00074                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00075                 double angleTolerance,
00076                 bool quad,
00077                 int trianglePixelSize,
00078                 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
00079 std::vector<pcl::Vertices> RTABMAP_EXP organizedFastMesh(
00080                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00081                 double angleTolerance = M_PI/16,
00082                 bool quad=true,
00083                 int trianglePixelSize = 2,
00084                 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
00085 std::vector<pcl::Vertices> RTABMAP_EXP organizedFastMesh(
00086                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00087                 double angleTolerance = M_PI/16,
00088                 bool quad=true,
00089                 int trianglePixelSize = 2,
00090                 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
00091 
00092 void RTABMAP_EXP appendMesh(
00093                 pcl::PointCloud<pcl::PointXYZRGBNormal> & cloudA,
00094                 std::vector<pcl::Vertices> & polygonsA,
00095                 const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloudB,
00096                 const std::vector<pcl::Vertices> & polygonsB);
00097 void RTABMAP_EXP appendMesh(
00098                 pcl::PointCloud<pcl::PointXYZRGB> & cloudA,
00099                 std::vector<pcl::Vertices> & polygonsA,
00100                 const pcl::PointCloud<pcl::PointXYZRGB> & cloudB,
00101                 const std::vector<pcl::Vertices> & polygonsB);
00102 
00103 // return map from new to old polygon indices
00104 std::vector<int> RTABMAP_EXP filterNotUsedVerticesFromMesh(
00105                 const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
00106                 const std::vector<pcl::Vertices> & polygons,
00107                 pcl::PointCloud<pcl::PointXYZRGBNormal> & outputCloud,
00108                 std::vector<pcl::Vertices> & outputPolygons);
00109 std::vector<int> RTABMAP_EXP filterNotUsedVerticesFromMesh(
00110                 const pcl::PointCloud<pcl::PointXYZRGB> & cloud,
00111                 const std::vector<pcl::Vertices> & polygons,
00112                 pcl::PointCloud<pcl::PointXYZRGB> & outputCloud,
00113                 std::vector<pcl::Vertices> & outputPolygons);
00114 std::vector<int> RTABMAP_EXP filterNaNPointsFromMesh(
00115                 const pcl::PointCloud<pcl::PointXYZRGB> & cloud,
00116                 const std::vector<pcl::Vertices> & polygons,
00117                 pcl::PointCloud<pcl::PointXYZRGB> & outputCloud,
00118                 std::vector<pcl::Vertices> & outputPolygons);
00119 
00120 std::vector<pcl::Vertices> RTABMAP_EXP filterCloseVerticesFromMesh(
00121                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud,
00122                 const std::vector<pcl::Vertices> & polygons,
00123                 float radius,
00124                 float angle,
00125                 bool keepLatestInRadius);
00126 
00127 std::vector<pcl::Vertices> RTABMAP_EXP filterInvalidPolygons(
00128                 const std::vector<pcl::Vertices> & polygons);
00129 
00130 pcl::PolygonMesh::Ptr RTABMAP_EXP createMesh(
00131                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloudWithNormals,
00132                 float gp3SearchRadius = 0.025,
00133                 float gp3Mu = 2.5,
00134                 int gp3MaximumNearestNeighbors = 100,
00135                 float gp3MaximumSurfaceAngle = M_PI/4,
00136                 float gp3MinimumAngle = M_PI/18,
00137                 float gp3MaximumAngle = 2*M_PI/3,
00138                 bool gp3NormalConsistency = true);
00139 
00140 pcl::TextureMesh::Ptr RTABMAP_EXP createTextureMesh(
00141                 const pcl::PolygonMesh::Ptr & mesh,
00142                 const std::map<int, Transform> & poses,
00143                 const std::map<int, CameraModel> & cameraModels,
00144                 const std::map<int, cv::Mat> & cameraDepths,
00145                 float maxDistance = 0.0f, // max camera distance to polygon to apply texture
00146                 float maxDepthError = 0.0f, // maximum depth error between reprojected mesh and depth image to texture a face (-1=disabled, 0=edge length is used)
00147                 float maxAngle = 0.0f, // maximum angle between camera and face (0=disabled)
00148                 int minClusterSize = 50, // minimum size of polygons clusters textured
00149                 const std::vector<float> & roiRatios = std::vector<float>(), // [left, right, top, bottom] region of interest (in ratios) of the image projected.
00150                 const ProgressState * state = 0,
00151                 std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0);
00152 pcl::TextureMesh::Ptr RTABMAP_EXP createTextureMesh(
00153                 const pcl::PolygonMesh::Ptr & mesh,
00154                 const std::map<int, Transform> & poses,
00155                 const std::map<int, std::vector<CameraModel> > & cameraModels,
00156                 const std::map<int, cv::Mat> & cameraDepths,
00157                 float maxDistance = 0.0f, // max camera distance to polygon to apply texture
00158                 float maxDepthError = 0.0f, // maximum depth error between reprojected mesh and depth image to texture a face (-1=disabled, 0=edge length is used)
00159                 float maxAngle = 0.0f, // maximum angle between camera and face (0=disabled)
00160                 int minClusterSize = 50, // minimum size of polygons clusters textured
00161                 const std::vector<float> & roiRatios = std::vector<float>(), // [left, right, top, bottom] region of interest (in ratios) of the image projected.
00162                 const ProgressState * state = 0,
00163                 std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0);
00164 
00168 void RTABMAP_EXP cleanTextureMesh(
00169                 pcl::TextureMesh & textureMesh,
00170                 int minClusterSize);
00171 
00172 pcl::TextureMesh::Ptr RTABMAP_EXP concatenateTextureMeshes(
00173                 const std::list<pcl::TextureMesh::Ptr> & meshes);
00174 
00175 void RTABMAP_EXP concatenateTextureMaterials(
00176                 pcl::TextureMesh & mesh, const cv::Size & imageSize, int textureSize, int maxTextures, float & scale, std::vector<bool> * materialsKept=0);
00177 
00178 std::vector<std::vector<unsigned int> > RTABMAP_EXP convertPolygonsFromPCL(
00179                 const std::vector<pcl::Vertices> & polygons);
00180 std::vector<std::vector<std::vector<unsigned int> > > RTABMAP_EXP convertPolygonsFromPCL(
00181                 const std::vector<std::vector<pcl::Vertices> > & polygons);
00182 std::vector<pcl::Vertices> RTABMAP_EXP convertPolygonsToPCL(
00183                 const std::vector<std::vector<unsigned int> > & polygons);
00184 std::vector<std::vector<pcl::Vertices> > RTABMAP_EXP convertPolygonsToPCL(
00185                 const std::vector<std::vector<std::vector<unsigned int> > > & tex_polygons);
00186 
00187 pcl::TextureMesh::Ptr RTABMAP_EXP assembleTextureMesh(
00188                 const cv::Mat & cloudMat,
00189                 const std::vector<std::vector<std::vector<unsigned int> > > & polygons,
00190 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
00191                 const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords,
00192 #else
00193                 const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
00194 #endif
00195                 cv::Mat & textures,
00196                 bool mergeTextures = false);
00197 
00198 pcl::PolygonMesh::Ptr RTABMAP_EXP assemblePolygonMesh(
00199                 const cv::Mat & cloudMat,
00200                 const std::vector<std::vector<unsigned int> > & polygons);
00201 
00206 cv::Mat RTABMAP_EXP mergeTextures(
00207                 pcl::TextureMesh & mesh,
00208                 const std::map<int, cv::Mat> & images, // raw or compressed, can be empty if memory or dbDriver should be used
00209                 const std::map<int, CameraModel> & calibrations, // Should match images
00210                 const Memory * memory = 0,             // Should be set if images are not set
00211                 const DBDriver * dbDriver = 0,         // Should be set if images and memory are not set
00212                 int textureSize = 4096,
00213                 int textureCount = 1,
00214                 const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels = std::vector<std::map<int, pcl::PointXY> >(), // needed for parameters below
00215                 bool gainCompensation = true,
00216                 float gainBeta = 10.0f,
00217                 bool gainRGB = true,                 //Do gain compensation on each channel
00218                 bool blending = true,
00219                 int blendingDecimation = 0,          //0=auto depending on projected polygon size and texture size
00220                 int brightnessContrastRatioLow = 0,  //0=disabled, values between 0 and 100
00221                 int brightnessContrastRatioHigh = 0, //0=disabled, values between 0 and 100
00222                 bool exposureFusion = false,         //Exposure fusion can be used only with OpenCV3
00223                 const ProgressState * state = 0);
00224 cv::Mat RTABMAP_EXP mergeTextures(
00225                 pcl::TextureMesh & mesh,
00226                 const std::map<int, cv::Mat> & images, // raw or compressed, can be empty if memory or dbDriver should be used
00227                 const std::map<int, std::vector<CameraModel> > & calibrations, // Should match images
00228                 const Memory * memory = 0,             // Should be set if images are not set
00229                 const DBDriver * dbDriver = 0,         // Should be set if images and memory are not set
00230                 int textureSize = 4096,
00231                 int textureCount = 1,
00232                 const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels = std::vector<std::map<int, pcl::PointXY> >(), // needed for parameters below
00233                 bool gainCompensation = true,
00234                 float gainBeta = 10.0f,
00235                 bool gainRGB = true,                 //Do gain compensation on each channel
00236                 bool blending = true,
00237                 int blendingDecimation = 0,          //0=auto depending on projected polygon size and texture size
00238                 int brightnessContrastRatioLow = 0,  //0=disabled, values between 0 and 100
00239                 int brightnessContrastRatioHigh = 0, //0=disabled, values between 0 and 100
00240                 bool exposureFusion = false,         //Exposure fusion can be used only with OpenCV3
00241                 const ProgressState * state = 0);
00242 
00243 void RTABMAP_EXP fixTextureMeshForVisualization(pcl::TextureMesh & textureMesh);
00244 
00245 cv::Mat RTABMAP_EXP computeNormals(
00246                 const cv::Mat & laserScan,
00247                 int searchK,
00248                 float searchRadius);
00249 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
00250                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00251                 int searchK = 20,
00252                 float searchRadius = 0.0f,
00253                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00254 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
00255                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00256                 int searchK = 20,
00257                 float searchRadius = 0.0f,
00258                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00259 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
00260                 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
00261                 int searchK = 20,
00262                 float searchRadius = 0.0f,
00263                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00264 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
00265                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00266                 const pcl::IndicesPtr & indices,
00267                 int searchK = 20,
00268                 float searchRadius = 0.0f,
00269                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00270 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
00271                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00272                 const pcl::IndicesPtr & indices,
00273                 int searchK = 20,
00274                 float searchRadius = 0.0f,
00275                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00276 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
00277                 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
00278                 const pcl::IndicesPtr & indices,
00279                 int searchK = 20,
00280                 float searchRadius = 0.0f,
00281                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00282 
00283 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals2D(
00284                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00285                 int searchK = 5,
00286                 float searchRadius = 0.0f,
00287                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00288 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals2D(
00289                 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
00290                 int searchK = 5,
00291                 float searchRadius = 0.0f,
00292                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00293 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals2D(
00294                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00295                 int searchK = 5,
00296                 float searchRadius = 0.0f,
00297                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00298 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals2D(
00299                 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
00300                 int searchK = 5,
00301                 float searchRadius = 0.0f,
00302                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00303 
00304 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals(
00305                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00306                 float maxDepthChangeFactor = 0.02f,
00307                 float normalSmoothingSize = 10.0f,
00308                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00309 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals(
00310                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00311                 const pcl::IndicesPtr & indices,
00312                 float maxDepthChangeFactor = 0.02f,
00313                 float normalSmoothingSize = 10.0f,
00314                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00315 
00316 float RTABMAP_EXP computeNormalsComplexity(
00317                 const LaserScan & scan,
00318                 cv::Mat * pcaEigenVectors = 0,
00319                 cv::Mat * pcaEigenValues = 0);
00320 float RTABMAP_EXP computeNormalsComplexity(
00321                 const pcl::PointCloud<pcl::Normal> & normals,
00322                 bool is2d = false,
00323                 cv::Mat * pcaEigenVectors = 0,
00324                 cv::Mat * pcaEigenValues = 0);
00325 float RTABMAP_EXP computeNormalsComplexity(
00326                 const pcl::PointCloud<pcl::PointNormal> & cloud,
00327                 bool is2d = false,
00328                 cv::Mat * pcaEigenVectors = 0,
00329                 cv::Mat * pcaEigenValues = 0);
00330 float RTABMAP_EXP computeNormalsComplexity(
00331                 const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
00332                 bool is2d = false,
00333                 cv::Mat * pcaEigenVectors = 0,
00334                 cv::Mat * pcaEigenValues = 0);
00335 
00336 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP mls(
00337                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00338                 float searchRadius = 0.0f,
00339                 int polygonialOrder = 2,
00340                 int upsamplingMethod = 0, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
00341                 float upsamplingRadius = 0.0f,   // SAMPLE_LOCAL_PLANE
00342                 float upsamplingStep = 0.0f,     // SAMPLE_LOCAL_PLANE
00343                 int pointDensity = 0,            // RANDOM_UNIFORM_DENSITY
00344                 float dilationVoxelSize = 1.0f,  // VOXEL_GRID_DILATION
00345                 int dilationIterations = 0);     // VOXEL_GRID_DILATION
00346 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP mls(
00347                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00348                 const pcl::IndicesPtr & indices,
00349                 float searchRadius = 0.0f,
00350                 int polygonialOrder = 2,
00351                 int upsamplingMethod = 0, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
00352                 float upsamplingRadius = 0.0f,   // SAMPLE_LOCAL_PLANE
00353                 float upsamplingStep = 0.0f,     // SAMPLE_LOCAL_PLANE
00354                 int pointDensity = 0,            // RANDOM_UNIFORM_DENSITY
00355                 float dilationVoxelSize = 1.0f,  // VOXEL_GRID_DILATION
00356                 int dilationIterations = 0);     // VOXEL_GRID_DILATION
00357 
00358 LaserScan RTABMAP_EXP adjustNormalsToViewPoint(
00359                 const LaserScan & scan,
00360                 const Eigen::Vector3f & viewpoint,
00361                 bool forceGroundNormalsUp);
00362 void RTABMAP_EXP adjustNormalsToViewPoint(
00363                 pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00364                 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
00365                 bool forceGroundNormalsUp = false);
00366 void RTABMAP_EXP adjustNormalsToViewPoint(
00367                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00368                 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
00369                 bool forceGroundNormalsUp = false);
00370 void RTABMAP_EXP adjustNormalsToViewPoints(
00371                 const std::map<int, Transform> & poses,
00372                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
00373                 const std::vector<int> & rawCameraIndices,
00374                 pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
00375 void RTABMAP_EXP adjustNormalsToViewPoints(
00376                 const std::map<int, Transform> & poses,
00377                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
00378                 const std::vector<int> & rawCameraIndices,
00379                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
00380 
00381 pcl::PolygonMesh::Ptr RTABMAP_EXP meshDecimation(const pcl::PolygonMesh::Ptr & mesh, float factor);
00382 
00383 template<typename pointT>
00384 std::vector<pcl::Vertices> normalizePolygonsSide(
00385                 const pcl::PointCloud<pointT> & cloud,
00386                 const std::vector<pcl::Vertices> & polygons,
00387                 const pcl::PointXYZ & viewPoint = pcl::PointXYZ(0,0,0));
00388 
00389 template<typename pointRGBT>
00390 void denseMeshPostProcessing(
00391                 pcl::PolygonMeshPtr & mesh,
00392                 float meshDecimationFactor = 0.0f, // value between 0 and 1, 0=disabled
00393                 int maximumPolygons = 0,           // 0=disabled
00394                 const typename pcl::PointCloud<pointRGBT>::Ptr & cloud = pcl::PointCloud<pointRGBT>::Ptr(), // A RGB point cloud used to transfer colors back to mesh (needed for parameters below)
00395                 float transferColorRadius = 0.05f, // <0=disabled, 0=nearest color
00396                 bool coloredOutput = true,         // Not used anymore, output is colored if transferColorRadius>=0
00397                 bool cleanMesh = true,             // Remove polygons not colored (if coloredOutput is disabled, transferColorRadius is still used to clean the mesh)
00398                 int minClusterSize = 50,           // Remove small polygon clusters after the mesh has been cleaned (0=disabled)
00399                 ProgressState * progressState = 0);
00400 
00401 } // namespace util3d
00402 } // namespace rtabmap
00403 
00404 #include "rtabmap/core/impl/util3d_surface.hpp"
00405 
00406 #endif /* UTIL3D_SURFACE_H_ */


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