util3d_surface.cpp
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 #include "rtabmap/core/util3d_surface.h"
00029 #include "rtabmap/core/util3d_filtering.h"
00030 #include "rtabmap/utilite/ULogger.h"
00031 #include "rtabmap/utilite/UDirectory.h"
00032 #include "rtabmap/utilite/UConversion.h"
00033 #include <pcl/search/kdtree.h>
00034 #include <pcl/surface/gp3.h>
00035 #include <pcl/features/normal_3d_omp.h>
00036 #include <pcl/surface/mls.h>
00037 #include <pcl/surface/texture_mapping.h>
00038 #include <pcl/features/integral_image_normal.h>
00039 
00040 #ifndef DISABLE_VTK
00041 #include <pcl/surface/vtk_smoothing/vtk_mesh_quadric_decimation.h>
00042 #endif
00043 
00044 #if PCL_VERSION_COMPARE(<, 1, 8, 0)
00045 #include "pcl18/surface/organized_fast_mesh.h"
00046 #else
00047 #include <pcl/surface/organized_fast_mesh.h>
00048 #include <pcl/surface/impl/marching_cubes.hpp>
00049 #include <pcl/surface/impl/organized_fast_mesh.hpp>
00050 #include <pcl/impl/instantiate.hpp>
00051 #include <pcl/point_types.h>
00052 
00053 // Instantiations of specific point types
00054 PCL_INSTANTIATE(OrganizedFastMesh, (pcl::PointXYZRGBNormal))
00055 
00056 #include <pcl/features/impl/normal_3d_omp.hpp>
00057 PCL_INSTANTIATE_PRODUCT(NormalEstimationOMP, ((pcl::PointXYZRGB))((pcl::Normal)))
00058 #endif
00059 
00060 namespace rtabmap
00061 {
00062 
00063 namespace util3d
00064 {
00065 
00066 void createPolygonIndexes(
00067                 const std::vector<pcl::Vertices> & polygons,
00068                 int cloudSize,
00069                 std::vector<std::set<int> > & neighbors,
00070                 std::vector<std::set<int> > & vertexToPolygons)
00071 {
00072         vertexToPolygons = std::vector<std::set<int> >(cloudSize);
00073         neighbors = std::vector<std::set<int> >(polygons.size());
00074 
00075         for(unsigned int i=0; i<polygons.size(); ++i)
00076         {
00077                 std::set<int> vertices(polygons[i].vertices.begin(), polygons[i].vertices.end());
00078 
00079                 for(unsigned int j=0; j<polygons[i].vertices.size(); ++j)
00080                 {
00081                         int v = polygons[i].vertices.at(j);
00082                         for(std::set<int>::iterator iter=vertexToPolygons[v].begin(); iter!=vertexToPolygons[v].end(); ++iter)
00083                         {
00084                                 int numSharedVertices = 0;
00085                                 for(unsigned int k=0; k<polygons.at(*iter).vertices.size() && numSharedVertices<2; ++k)
00086                                 {
00087                                         if(vertices.find(polygons.at(*iter).vertices.at(k)) != vertices.end())
00088                                         {
00089                                                 ++numSharedVertices;
00090                                         }
00091                                 }
00092                                 if(numSharedVertices >= 2)
00093                                 {
00094                                         neighbors[*iter].insert(i);
00095                                         neighbors[i].insert(*iter);
00096                                 }
00097                         }
00098                         vertexToPolygons[v].insert(i);
00099                 }
00100         }
00101 }
00102 
00103 std::vector<pcl::Vertices> organizedFastMesh(
00104                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00105                 double angleTolerance,
00106                 bool quad,
00107                 int trianglePixelSize,
00108                 const Eigen::Vector3f & viewpoint)
00109 {
00110         UDEBUG("size=%d angle=%f quad=%d triangleSize=%d", (int)cloud->size(), angleTolerance, quad?1:0, trianglePixelSize);
00111         UASSERT(cloud->is_dense == false);
00112         UASSERT(cloud->width > 1 && cloud->height > 1);
00113 
00114         pcl::OrganizedFastMesh<pcl::PointXYZRGB> ofm;
00115         ofm.setTrianglePixelSize (trianglePixelSize);
00116         ofm.setTriangulationType (quad?pcl::OrganizedFastMesh<pcl::PointXYZRGB>::QUAD_MESH:pcl::OrganizedFastMesh<pcl::PointXYZRGB>::TRIANGLE_RIGHT_CUT);
00117         ofm.setInputCloud (cloud);
00118         ofm.setAngleTolerance(angleTolerance);
00119         ofm.setViewpoint(viewpoint);
00120 
00121         std::vector<pcl::Vertices> vertices;
00122         ofm.reconstruct (vertices);
00123 
00124         if(quad)
00125         {
00126                 //flip all polygons (right handed)
00127                 std::vector<pcl::Vertices> output(vertices.size());
00128                 for(unsigned int i=0; i<vertices.size(); ++i)
00129                 {
00130                         output[i].vertices.resize(4);
00131                         output[i].vertices[0] = vertices[i].vertices[0];
00132                         output[i].vertices[3] = vertices[i].vertices[1];
00133                         output[i].vertices[2] = vertices[i].vertices[2];
00134                         output[i].vertices[1] = vertices[i].vertices[3];
00135                 }
00136                 return output;
00137         }
00138 
00139         return vertices;
00140 }
00141 std::vector<pcl::Vertices> organizedFastMesh(
00142                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00143                 double angleTolerance,
00144                 bool quad,
00145                 int trianglePixelSize,
00146                 const Eigen::Vector3f & viewpoint)
00147 {
00148         UDEBUG("size=%d angle=%f quad=%d triangleSize=%d", (int)cloud->size(), angleTolerance, quad?1:0, trianglePixelSize);
00149         UASSERT(cloud->is_dense == false);
00150         UASSERT(cloud->width > 1 && cloud->height > 1);
00151 
00152         pcl::OrganizedFastMesh<pcl::PointXYZRGBNormal> ofm;
00153         ofm.setTrianglePixelSize (trianglePixelSize);
00154         ofm.setTriangulationType (quad?pcl::OrganizedFastMesh<pcl::PointXYZRGBNormal>::QUAD_MESH:pcl::OrganizedFastMesh<pcl::PointXYZRGBNormal>::TRIANGLE_RIGHT_CUT);
00155         ofm.setInputCloud (cloud);
00156         ofm.setAngleTolerance(angleTolerance);
00157         ofm.setViewpoint(viewpoint);
00158 
00159         std::vector<pcl::Vertices> vertices;
00160         ofm.reconstruct (vertices);
00161 
00162         if(quad)
00163         {
00164                 //flip all polygons (right handed)
00165                 std::vector<pcl::Vertices> output(vertices.size());
00166                 for(unsigned int i=0; i<vertices.size(); ++i)
00167                 {
00168                         output[i].vertices.resize(4);
00169                         output[i].vertices[0] = vertices[i].vertices[0];
00170                         output[i].vertices[3] = vertices[i].vertices[1];
00171                         output[i].vertices[2] = vertices[i].vertices[2];
00172                         output[i].vertices[1] = vertices[i].vertices[3];
00173                 }
00174                 return output;
00175         }
00176 
00177         return vertices;
00178 }
00179 
00180 void appendMesh(
00181                 pcl::PointCloud<pcl::PointXYZRGBNormal> & cloudA,
00182                 std::vector<pcl::Vertices> & polygonsA,
00183                 const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloudB,
00184                 const std::vector<pcl::Vertices> & polygonsB)
00185 {
00186         UDEBUG("cloudA=%d polygonsA=%d cloudB=%d polygonsB=%d", (int)cloudA.size(), (int)polygonsA.size(), (int)cloudB.size(), (int)polygonsB.size());
00187         UASSERT(!cloudA.isOrganized() && !cloudB.isOrganized());
00188 
00189         int sizeA = (int)cloudA.size();
00190         cloudA += cloudB;
00191 
00192         int sizePolygonsA = (int)polygonsA.size();
00193         polygonsA.resize(sizePolygonsA+polygonsB.size());
00194 
00195         for(unsigned int i=0; i<polygonsB.size(); ++i)
00196         {
00197                 pcl::Vertices vertices = polygonsB[i];
00198                 for(unsigned int j=0; j<vertices.vertices.size(); ++j)
00199                 {
00200                         vertices.vertices[j] += sizeA;
00201                 }
00202                 polygonsA[i+sizePolygonsA] = vertices;
00203         }
00204 }
00205 
00206 void appendMesh(
00207                 pcl::PointCloud<pcl::PointXYZRGB> & cloudA,
00208                 std::vector<pcl::Vertices> & polygonsA,
00209                 const pcl::PointCloud<pcl::PointXYZRGB> & cloudB,
00210                 const std::vector<pcl::Vertices> & polygonsB)
00211 {
00212         UDEBUG("cloudA=%d polygonsA=%d cloudB=%d polygonsB=%d", (int)cloudA.size(), (int)polygonsA.size(), (int)cloudB.size(), (int)polygonsB.size());
00213         UASSERT(!cloudA.isOrganized() && !cloudB.isOrganized());
00214 
00215         int sizeA = (int)cloudA.size();
00216         cloudA += cloudB;
00217 
00218         int sizePolygonsA = (int)polygonsA.size();
00219         polygonsA.resize(sizePolygonsA+polygonsB.size());
00220 
00221         for(unsigned int i=0; i<polygonsB.size(); ++i)
00222         {
00223                 pcl::Vertices vertices = polygonsB[i];
00224                 for(unsigned int j=0; j<vertices.vertices.size(); ++j)
00225                 {
00226                         vertices.vertices[j] += sizeA;
00227                 }
00228                 polygonsA[i+sizePolygonsA] = vertices;
00229         }
00230 }
00231 
00232 std::map<int, int> filterNotUsedVerticesFromMesh(
00233                 const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
00234                 const std::vector<pcl::Vertices> & polygons,
00235                 pcl::PointCloud<pcl::PointXYZRGBNormal> & outputCloud,
00236                 std::vector<pcl::Vertices> & outputPolygons)
00237 {
00238         UDEBUG("size=%d polygons=%d", (int)cloud.size(), (int)polygons.size());
00239         std::map<int, int> addedVertices; //<oldIndex, newIndex>
00240         std::map<int, int> output; //<newIndex, oldIndex>
00241         outputCloud.resize(cloud.size());
00242         outputCloud.is_dense = true;
00243         outputPolygons.resize(polygons.size());
00244         int oi = 0;
00245         for(unsigned int i=0; i<polygons.size(); ++i)
00246         {
00247                 pcl::Vertices & v = outputPolygons[i];
00248                 v.vertices.resize(polygons[i].vertices.size());
00249                 for(unsigned int j=0; j<polygons[i].vertices.size(); ++j)
00250                 {
00251                         std::map<int, int>::iterator iter = addedVertices.find(polygons[i].vertices[j]);
00252                         if(iter == addedVertices.end())
00253                         {
00254                                 outputCloud[oi] = cloud.at(polygons[i].vertices[j]);
00255                                 addedVertices.insert(std::make_pair(polygons[i].vertices[j], oi));
00256                                 output.insert(std::make_pair(oi, polygons[i].vertices[j]));
00257                                 v.vertices[j] = oi++;
00258                         }
00259                         else
00260                         {
00261                                 v.vertices[j] = iter->second;
00262                         }
00263                 }
00264         }
00265         outputCloud.resize(oi);
00266 
00267         return output;
00268 }
00269 
00270 std::map<int, int> filterNotUsedVerticesFromMesh(
00271                 const pcl::PointCloud<pcl::PointXYZRGB> & cloud,
00272                 const std::vector<pcl::Vertices> & polygons,
00273                 pcl::PointCloud<pcl::PointXYZRGB> & outputCloud,
00274                 std::vector<pcl::Vertices> & outputPolygons)
00275 {
00276         UDEBUG("size=%d polygons=%d", (int)cloud.size(), (int)polygons.size());
00277         std::map<int, int> addedVertices; //<oldIndex, newIndex>
00278         std::map<int, int> output; //<newIndex, oldIndex>
00279         outputCloud.resize(cloud.size());
00280         outputCloud.is_dense = true;
00281         outputPolygons.resize(polygons.size());
00282         int oi = 0;
00283         for(unsigned int i=0; i<polygons.size(); ++i)
00284         {
00285                 pcl::Vertices & v = outputPolygons[i];
00286                 v.vertices.resize(polygons[i].vertices.size());
00287                 for(unsigned int j=0; j<polygons[i].vertices.size(); ++j)
00288                 {
00289                         std::map<int, int>::iterator iter = addedVertices.find(polygons[i].vertices[j]);
00290                         if(iter == addedVertices.end())
00291                         {
00292                                 outputCloud[oi] = cloud.at(polygons[i].vertices[j]);
00293                                 addedVertices.insert(std::make_pair(polygons[i].vertices[j], oi));
00294                                 output.insert(std::make_pair(oi, polygons[i].vertices[j]));
00295                                 v.vertices[j] = oi++;
00296                         }
00297                         else
00298                         {
00299                                 v.vertices[j] = iter->second;
00300                         }
00301                 }
00302         }
00303         outputCloud.resize(oi);
00304 
00305         return output;
00306 }
00307 
00308 std::vector<pcl::Vertices> filterCloseVerticesFromMesh(
00309                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud,
00310                 const std::vector<pcl::Vertices> & polygons,
00311                 float radius,
00312                 float angle, // FIXME angle not used
00313                 bool keepLatestInRadius)
00314 {
00315         UDEBUG("size=%d polygons=%d radius=%f angle=%f keepLatest=%d",
00316                         (int)cloud->size(), (int)polygons.size(), radius, angle, keepLatestInRadius?1:0);
00317         std::vector<pcl::Vertices> outputPolygons;
00318         pcl::KdTreeFLANN<pcl::PointXYZRGBNormal>::Ptr kdtree(new pcl::KdTreeFLANN<pcl::PointXYZRGBNormal>);
00319         kdtree->setInputCloud(cloud);
00320 
00321         std::map<int, int> verticesDone;
00322         outputPolygons = polygons;
00323         for(unsigned int i=0; i<outputPolygons.size(); ++i)
00324         {
00325                 pcl::Vertices & polygon = outputPolygons[i];
00326                 for(unsigned int j=0; j<polygon.vertices.size(); ++j)
00327                 {
00328                         std::map<int, int>::iterator iter = verticesDone.find(polygon.vertices[j]);
00329                         if(iter != verticesDone.end())
00330                         {
00331                                 polygon.vertices[j] = iter->second;
00332                         }
00333                         else
00334                         {
00335                                 std::vector<int> kIndices;
00336                                 std::vector<float> kDistances;
00337                                 kdtree->radiusSearch(polygon.vertices[j], radius, kIndices, kDistances);
00338                                 if(kIndices.size())
00339                                 {
00340                                         int reference = -1;
00341                                         for(unsigned int z=0; z<kIndices.size(); ++z)
00342                                         {
00343                                                 if(reference == -1)
00344                                                 {
00345                                                         reference = kIndices[z];
00346                                                 }
00347                                                 else if(keepLatestInRadius)
00348                                                 {
00349                                                         if(kIndices[z] < reference)
00350                                                         {
00351                                                                 reference = kIndices[z];
00352                                                         }
00353                                                 }
00354                                                 else
00355                                                 {
00356                                                         if(kIndices[z] > reference)
00357                                                         {
00358                                                                 reference = kIndices[z];
00359                                                         }
00360                                                 }
00361                                         }
00362                                         if(reference >= 0)
00363                                         {
00364                                                 for(unsigned int z=0; z<kIndices.size(); ++z)
00365                                                 {
00366                                                         verticesDone.insert(std::make_pair(kIndices[j], reference));
00367                                                 }
00368                                                 polygon.vertices[j] = reference;
00369                                         }
00370                                 }
00371                                 else
00372                                 {
00373                                         verticesDone.insert(std::make_pair(polygon.vertices[j], polygon.vertices[j]));
00374                                 }
00375                         }
00376                 }
00377         }
00378         return outputPolygons;
00379 }
00380 
00381 std::vector<pcl::Vertices> filterInvalidPolygons(const std::vector<pcl::Vertices> & polygons)
00382 {
00383         std::vector<pcl::Vertices> output(polygons.size());
00384         int oi=0;
00385         for(unsigned int i=0; i<polygons.size(); ++i)
00386         {
00387                 bool valid = true;
00388                 for(unsigned int j=0; j<polygons[i].vertices.size(); ++j)
00389                 {
00390                         if(polygons[i].vertices[j] == polygons[i].vertices[(j+1)%polygons[i].vertices.size()])
00391                         {
00392                                 valid = false;
00393                                 break;
00394                         }
00395                 }
00396                 if(valid)
00397                 {
00398                         output[oi++] = polygons[i];
00399                 }
00400         }
00401         output.resize(oi);
00402         return output;
00403 }
00404 
00405 pcl::PolygonMesh::Ptr createMesh(
00406                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloudWithNormals,
00407                 float gp3SearchRadius,
00408                 float gp3Mu,
00409                 int gp3MaximumNearestNeighbors,
00410                 float gp3MaximumSurfaceAngle,
00411                 float gp3MinimumAngle,
00412                 float gp3MaximumAngle,
00413                 bool gp3NormalConsistency)
00414 {
00415         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudWithNormalsNoNaN = removeNaNNormalsFromPointCloud(cloudWithNormals);
00416 
00417         // Create search tree*
00418         pcl::search::KdTree<pcl::PointXYZRGBNormal>::Ptr tree2 (new pcl::search::KdTree<pcl::PointXYZRGBNormal>);
00419         tree2->setInputCloud (cloudWithNormalsNoNaN);
00420 
00421         // Initialize objects
00422         pcl::GreedyProjectionTriangulation<pcl::PointXYZRGBNormal> gp3;
00423         pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
00424 
00425         // Set the maximum distance between connected points (maximum edge length)
00426         gp3.setSearchRadius (gp3SearchRadius);
00427 
00428         // Set typical values for the parameters
00429         gp3.setMu (gp3Mu);
00430         gp3.setMaximumNearestNeighbors (gp3MaximumNearestNeighbors);
00431         gp3.setMaximumSurfaceAngle(gp3MaximumSurfaceAngle); // 45 degrees
00432         gp3.setMinimumAngle(gp3MinimumAngle); // 10 degrees
00433         gp3.setMaximumAngle(gp3MaximumAngle); // 120 degrees
00434         gp3.setNormalConsistency(gp3NormalConsistency);
00435         gp3.setConsistentVertexOrdering(gp3NormalConsistency);
00436 
00437         // Get result
00438         gp3.setInputCloud (cloudWithNormalsNoNaN);
00439         gp3.setSearchMethod (tree2);
00440         gp3.reconstruct (*mesh);
00441 
00442         //UASSERT(mesh->cloud.data.size()/mesh->cloud.point_step == cloudWithNormalsNoNaN->size());
00443         //mesh->polygons = normalizePolygonsSide(*cloudWithNormalsNoNaN, mesh->polygons);
00444 
00445         return mesh;
00446 }
00447 
00448 pcl::texture_mapping::CameraVector createTextureCameras(
00449                 const std::map<int, Transform> & poses,
00450                 const std::map<int, CameraModel> & cameraModels,
00451                 const std::map<int, cv::Mat> & images,
00452                 const std::string & tmpDirectory)
00453 {
00454         UASSERT(poses.size() == cameraModels.size() && poses.size() == images.size());
00455         UASSERT(UDirectory::exists(tmpDirectory));
00456         pcl::texture_mapping::CameraVector cameras(poses.size());
00457         std::map<int, Transform>::const_iterator poseIter=poses.begin();
00458         std::map<int, CameraModel>::const_iterator modelIter=cameraModels.begin();
00459         std::map<int, cv::Mat>::const_iterator imageIter=images.begin();
00460         int oi=0;
00461         for(; poseIter!=poses.end(); ++poseIter, ++modelIter, ++imageIter)
00462         {
00463                 UASSERT(poseIter->first == modelIter->first);
00464                 UASSERT(poseIter->first == imageIter->first);
00465                 pcl::TextureMapping<pcl::PointXYZ>::Camera cam;
00466 
00467                 // transform into optical referential
00468                 Transform rotation(0,-1,0,0,
00469                                                    0,0,-1,0,
00470                                                    1,0,0,0);
00471 
00472                 Transform t = poseIter->second*rotation.inverse();
00473 
00474                 cam.pose = t.toEigen3f();
00475 
00476                 UASSERT(modelIter->second.fx()>0 && imageIter->second.rows>0 && imageIter->second.cols>0);
00477                 cam.focal_length=modelIter->second.fx();
00478                 cam.height=imageIter->second.rows;
00479                 cam.width=imageIter->second.cols;
00480 
00481 
00482                 std::string fileName = uFormat("%s/%s%d.png", tmpDirectory.c_str(), "texture_", poseIter->first);
00483                 if(!cv::imwrite(fileName, imageIter->second))
00484                 {
00485                         UERROR("Cannot save texture of image %d", poseIter->first);
00486                 }
00487                 else
00488                 {
00489                         UINFO("Saved temporary texture: \"%s\"", fileName.c_str());
00490                 }
00491                 cam.texture_file = fileName;
00492                 cameras[oi++] = cam;
00493         }
00494         return cameras;
00495 }
00496 
00497 pcl::TextureMesh::Ptr createTextureMesh(
00498                 const pcl::PolygonMesh::Ptr & mesh,
00499                 const std::map<int, Transform> & poses,
00500                 const std::map<int, CameraModel> & cameraModels,
00501                 const std::map<int, cv::Mat> & images,
00502                 const std::string & tmpDirectory,
00503                 int kNormalSearch)
00504 {
00505         pcl::TextureMesh::Ptr textureMesh(new pcl::TextureMesh);
00506         textureMesh->cloud = mesh->cloud;
00507         textureMesh->tex_polygons.push_back(mesh->polygons);
00508 
00509         // Original from pcl/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp:
00510         // Author: Raphael Favier, Technical University Eindhoven, (r.mysurname <aT> tue.nl)
00511 
00512         // Create the texturemesh object that will contain our UV-mapped mesh
00513 
00514         // create cameras
00515         pcl::texture_mapping::CameraVector cameras = createTextureCameras(
00516                         poses,
00517                         cameraModels,
00518                         images,
00519                         tmpDirectory);
00520 
00521         // Create materials for each texture (and one extra for occluded faces)
00522         textureMesh->tex_materials.resize (cameras.size () + 1);
00523         for(unsigned int i = 0 ; i <= cameras.size() ; ++i)
00524         {
00525                 pcl::TexMaterial mesh_material;
00526                 mesh_material.tex_Ka.r = 0.2f;
00527                 mesh_material.tex_Ka.g = 0.2f;
00528                 mesh_material.tex_Ka.b = 0.2f;
00529 
00530                 mesh_material.tex_Kd.r = 0.8f;
00531                 mesh_material.tex_Kd.g = 0.8f;
00532                 mesh_material.tex_Kd.b = 0.8f;
00533 
00534                 mesh_material.tex_Ks.r = 1.0f;
00535                 mesh_material.tex_Ks.g = 1.0f;
00536                 mesh_material.tex_Ks.b = 1.0f;
00537 
00538                 mesh_material.tex_d = 1.0f;
00539                 mesh_material.tex_Ns = 75.0f;
00540                 mesh_material.tex_illum = 2;
00541 
00542                 std::stringstream tex_name;
00543                 tex_name << "material_" << i;
00544                 tex_name >> mesh_material.tex_name;
00545 
00546                 if(i < cameras.size ())
00547                 {
00548                         mesh_material.tex_file = cameras[i].texture_file;
00549                 }
00550                 else
00551                 {
00552                         mesh_material.tex_file = tmpDirectory+UDirectory::separator()+"occluded.png";
00553                         cv::Mat emptyImage;
00554                         if(i>0)
00555                         {
00556                                 emptyImage = cv::Mat::zeros(cameras[i-1].height,cameras[i-1].width, CV_8UC1);
00557                         }
00558                         else
00559                         {
00560                                 emptyImage = cv::Mat::zeros(480, 640, CV_8UC1);
00561                         }
00562                         cv::imwrite(mesh_material.tex_file, emptyImage);
00563                 }
00564 
00565                 textureMesh->tex_materials[i] = mesh_material;
00566         }
00567 
00568         // Texture by projection
00569         pcl::TextureMapping<pcl::PointXYZ> tm; // TextureMapping object that will perform the sort
00570         tm.textureMeshwithMultipleCameras(*textureMesh, cameras);
00571 
00572         // compute normals for the mesh if not already here
00573         bool hasNormals = false;
00574         for(unsigned int i=0; i<textureMesh->cloud.fields.size(); ++i)
00575         {
00576                 if(textureMesh->cloud.fields[i].name.compare("normal_x") == 0)
00577                 {
00578                         hasNormals = true;
00579                         break;
00580                 }
00581         }
00582         if(!hasNormals)
00583         {
00584                 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00585                 pcl::fromPCLPointCloud2(textureMesh->cloud, *cloud);
00586                 pcl::PointCloud<pcl::Normal>::Ptr normals = computeNormals(cloud, kNormalSearch);
00587                 // Concatenate the XYZ and normal fields
00588                 pcl::PointCloud<pcl::PointNormal>::Ptr cloudWithNormals;
00589                 pcl::concatenateFields (*cloud, *normals, *cloudWithNormals);
00590                 pcl::toPCLPointCloud2 (*cloudWithNormals, textureMesh->cloud);
00591         }
00592 
00593         return textureMesh;
00594 }
00595 
00596 pcl::PointCloud<pcl::Normal>::Ptr computeNormals(
00597                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00598                 int normalKSearch,
00599                 const Eigen::Vector3f & viewPoint)
00600 {
00601         pcl::IndicesPtr indices(new std::vector<int>);
00602         return computeNormals(cloud, indices, normalKSearch, viewPoint);
00603 }
00604 pcl::PointCloud<pcl::Normal>::Ptr computeNormals(
00605                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00606                 const pcl::IndicesPtr & indices,
00607                 int normalKSearch,
00608                 const Eigen::Vector3f & viewPoint)
00609 {
00610         pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
00611         if(indices->size())
00612         {
00613                 tree->setInputCloud(cloud, indices);
00614         }
00615         else
00616         {
00617                 tree->setInputCloud (cloud);
00618         }
00619 
00620         // Normal estimation*
00621 #ifdef PCL_OMP
00622         pcl::NormalEstimationOMP<pcl::PointXYZ, pcl::Normal> n;
00623 #else
00624         pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> n;
00625 #endif
00626         pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal>);
00627         n.setInputCloud (cloud);
00628         // Commented: Keep the output normals size the same as the input cloud
00629         //if(indices->size())
00630         //{
00631         //      n.setIndices(indices);
00632         //}
00633         n.setSearchMethod (tree);
00634         n.setKSearch (normalKSearch);
00635         n.setViewPoint(viewPoint[0], viewPoint[1], viewPoint[2]);
00636         n.compute (*normals);
00637 
00638         return normals;
00639 }
00640 
00641 pcl::PointCloud<pcl::Normal>::Ptr computeNormals(
00642                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00643                 int normalKSearch,
00644                 const Eigen::Vector3f & viewPoint)
00645 {
00646         pcl::IndicesPtr indices(new std::vector<int>);
00647         return computeNormals(cloud, indices, normalKSearch, viewPoint);
00648 }
00649 pcl::PointCloud<pcl::Normal>::Ptr computeNormals(
00650                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00651                 const pcl::IndicesPtr & indices,
00652                 int normalKSearch,
00653                 const Eigen::Vector3f & viewPoint)
00654 {
00655         pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGB>);
00656         if(indices->size())
00657         {
00658                 tree->setInputCloud(cloud, indices);
00659         }
00660         else
00661         {
00662                 tree->setInputCloud (cloud);
00663         }
00664 
00665         // Normal estimation*
00666 #ifdef PCL_OMP
00667         pcl::NormalEstimationOMP<pcl::PointXYZRGB, pcl::Normal> n;
00668 #else
00669         pcl::NormalEstimation<pcl::PointXYZRGB, pcl::Normal> n;
00670 #endif
00671         pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal>);
00672         n.setInputCloud (cloud);
00673         // Commented: Keep the output normals size the same as the input cloud
00674         //if(indices->size())
00675         //{
00676         //      n.setIndices(indices);
00677         //}
00678         n.setSearchMethod (tree);
00679         n.setKSearch (normalKSearch);
00680         n.setViewPoint(viewPoint[0], viewPoint[1], viewPoint[2]);
00681         n.compute (*normals);
00682 
00683         return normals;
00684 }
00685 
00686 pcl::PointCloud<pcl::Normal>::Ptr computeFastOrganizedNormals(
00687                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00688                 float maxDepthChangeFactor,
00689                 float normalSmoothingSize,
00690                 const Eigen::Vector3f & viewPoint)
00691 {
00692         pcl::IndicesPtr indices(new std::vector<int>);
00693         return computeFastOrganizedNormals(cloud, indices, maxDepthChangeFactor, normalSmoothingSize, viewPoint);
00694 }
00695 pcl::PointCloud<pcl::Normal>::Ptr computeFastOrganizedNormals(
00696                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00697                 const pcl::IndicesPtr & indices,
00698                 float maxDepthChangeFactor,
00699                 float normalSmoothingSize,
00700                 const Eigen::Vector3f & viewPoint)
00701 {
00702         UASSERT(cloud->isOrganized());
00703 
00704         // Normal estimation
00705         pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal>);
00706         pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::Normal> ne;
00707         ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
00708         ne.setMaxDepthChangeFactor(maxDepthChangeFactor);
00709         ne.setNormalSmoothingSize(normalSmoothingSize);
00710         ne.setInputCloud(cloud);
00711         // Commented: Keep the output normals size the same as the input cloud
00712         //if(indices->size())
00713         //{
00714         //      ne.setIndices(indices);
00715         //}
00716         ne.setViewPoint(viewPoint[0], viewPoint[1], viewPoint[2]);
00717         ne.compute(*normals);
00718 
00719         return normals;
00720 }
00721 
00722 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mls(
00723                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00724                 float searchRadius,
00725                 int polygonialOrder,
00726                 int upsamplingMethod, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
00727                 float upsamplingRadius,      // SAMPLE_LOCAL_PLANE
00728                 float upsamplingStep,        // SAMPLE_LOCAL_PLANE
00729                 int pointDensity,             // RANDOM_UNIFORM_DENSITY
00730                 float dilationVoxelSize,     // VOXEL_GRID_DILATION
00731                 int dilationIterations)       // VOXEL_GRID_DILATION
00732 {
00733         pcl::IndicesPtr indices(new std::vector<int>);
00734         return mls(cloud,
00735                         indices,
00736                         searchRadius,
00737                         polygonialOrder,
00738                         upsamplingMethod,
00739                         upsamplingRadius,
00740                         upsamplingStep,
00741                         pointDensity,
00742                         dilationVoxelSize,
00743                         dilationIterations);
00744 }
00745 
00746 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mls(
00747                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00748                 const pcl::IndicesPtr & indices,
00749                 float searchRadius,
00750                 int polygonialOrder,
00751                 int upsamplingMethod, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
00752                 float upsamplingRadius,      // SAMPLE_LOCAL_PLANE
00753                 float upsamplingStep,        // SAMPLE_LOCAL_PLANE
00754                 int pointDensity,             // RANDOM_UNIFORM_DENSITY
00755                 float dilationVoxelSize,     // VOXEL_GRID_DILATION
00756                 int dilationIterations)       // VOXEL_GRID_DILATION
00757 {
00758         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud_with_normals(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00759         pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGB>);
00760         if(indices->size())
00761         {
00762                 tree->setInputCloud (cloud, indices);
00763         }
00764         else
00765         {
00766                 tree->setInputCloud (cloud);
00767         }
00768 
00769         // Init object (second point type is for the normals)
00770         pcl::MovingLeastSquares<pcl::PointXYZRGB, pcl::PointXYZRGBNormal> mls;
00771 
00772         // Set parameters
00773         mls.setComputeNormals (true);
00774         if(polygonialOrder > 0)
00775         {
00776                 mls.setPolynomialFit (true);
00777                 mls.setPolynomialOrder(polygonialOrder);
00778         }
00779         else
00780         {
00781                 mls.setPolynomialFit (false);
00782         }
00783         UASSERT(upsamplingMethod >= mls.NONE &&
00784                         upsamplingMethod <= mls.VOXEL_GRID_DILATION);
00785         mls.setUpsamplingMethod((pcl::MovingLeastSquares<pcl::PointXYZRGB, pcl::PointXYZRGBNormal>::UpsamplingMethod)upsamplingMethod);
00786         mls.setSearchRadius(searchRadius);
00787         mls.setUpsamplingRadius(upsamplingRadius);
00788         mls.setUpsamplingStepSize(upsamplingStep);
00789         mls.setPointDensity(pointDensity);
00790         mls.setDilationVoxelSize(dilationVoxelSize);
00791         mls.setDilationIterations(dilationIterations);
00792 
00793         // Reconstruct
00794         mls.setInputCloud (cloud);
00795         if(indices->size())
00796         {
00797                 mls.setIndices(indices);
00798         }
00799         mls.setSearchMethod (tree);
00800         mls.process (*cloud_with_normals);
00801 
00802         // It seems that returned normals are not normalized!? FIXME: Is it a bug only in PCL 1.7.1?
00803         for(unsigned int i=0; i<cloud_with_normals->size(); ++i)
00804         {
00805                 Eigen::Vector3f normal(cloud_with_normals->at(i).normal_x, cloud_with_normals->at(i).normal_y, cloud_with_normals->at(i).normal_z);
00806                 normal.normalize();
00807                 cloud_with_normals->at(i).normal_x = normal[0];
00808                 cloud_with_normals->at(i).normal_y = normal[1];
00809                 cloud_with_normals->at(i).normal_z = normal[2];
00810         }
00811 
00812         return cloud_with_normals;
00813 }
00814 
00815 void adjustNormalsToViewPoints(
00816                 const std::map<int, Transform> & poses,
00817                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
00818                 const std::vector<int> & rawCameraIndices,
00819                 pcl::PointCloud<pcl::PointNormal>::Ptr & cloud)
00820 {
00821         if(poses.size() && rawCloud->size() && rawCloud->size() == rawCameraIndices.size() && cloud->size())
00822         {
00823                 pcl::search::KdTree<pcl::PointXYZ>::Ptr rawTree (new pcl::search::KdTree<pcl::PointXYZ>);
00824                 rawTree->setInputCloud (rawCloud);
00825 
00826                 for(unsigned int i=0; i<cloud->size(); ++i)
00827                 {
00828                         pcl::PointXYZ normal(cloud->points[i].normal_x, cloud->points[i].normal_y, cloud->points[i].normal_z);
00829                         if(pcl::isFinite(normal))
00830                         {
00831                                 std::vector<int> indices;
00832                                 std::vector<float> dist;
00833                                 rawTree->nearestKSearch(pcl::PointXYZ(cloud->points[i].x, cloud->points[i].y, cloud->points[i].z), 1, indices, dist);
00834                                 UASSERT(indices.size() == 1);
00835                                 if(indices.size() && indices[0]>=0)
00836                                 {
00837                                         Transform p = poses.at(rawCameraIndices[indices[0]]);
00838                                         pcl::PointXYZ viewpoint(p.x(), p.y(), p.z());
00839                                         Eigen::Vector3f v = viewpoint.getVector3fMap() - cloud->points[i].getVector3fMap();
00840 
00841                                         Eigen::Vector3f n(normal.x, normal.y, normal.z);
00842 
00843                                         float result = v.dot(n);
00844                                         if(result < 0)
00845                                         {
00846                                                 //reverse normal
00847                                                 cloud->points[i].normal_x *= -1.0f;
00848                                                 cloud->points[i].normal_y *= -1.0f;
00849                                                 cloud->points[i].normal_z *= -1.0f;
00850                                         }
00851                                 }
00852                                 else
00853                                 {
00854                                         UWARN("Not found camera viewpoint for point %d", i);
00855                                 }
00856                         }
00857                 }
00858         }
00859 }
00860 
00861 void adjustNormalsToViewPoints(
00862                 const std::map<int, Transform> & poses,
00863                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
00864                 const std::vector<int> & rawCameraIndices,
00865                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud)
00866 {
00867         if(poses.size() && rawCloud->size() && rawCloud->size() == rawCameraIndices.size() && cloud->size())
00868         {
00869                 pcl::search::KdTree<pcl::PointXYZ>::Ptr rawTree (new pcl::search::KdTree<pcl::PointXYZ>);
00870                 rawTree->setInputCloud (rawCloud);
00871 
00872                 for(unsigned int i=0; i<cloud->size(); ++i)
00873                 {
00874                         pcl::PointXYZ normal(cloud->points[i].normal_x, cloud->points[i].normal_y, cloud->points[i].normal_z);
00875                         if(pcl::isFinite(normal))
00876                         {
00877                                 std::vector<int> indices;
00878                                 std::vector<float> dist;
00879                                 rawTree->nearestKSearch(pcl::PointXYZ(cloud->points[i].x, cloud->points[i].y, cloud->points[i].z), 1, indices, dist);
00880                                 UASSERT(indices.size() == 1);
00881                                 if(indices.size() && indices[0]>=0)
00882                                 {
00883                                         Transform p = poses.at(rawCameraIndices[indices[0]]);
00884                                         pcl::PointXYZ viewpoint(p.x(), p.y(), p.z());
00885                                         Eigen::Vector3f v = viewpoint.getVector3fMap() - cloud->points[i].getVector3fMap();
00886 
00887                                         Eigen::Vector3f n(normal.x, normal.y, normal.z);
00888 
00889                                         float result = v.dot(n);
00890                                         if(result < 0)
00891                                         {
00892                                                 //reverse normal
00893                                                 cloud->points[i].normal_x *= -1.0f;
00894                                                 cloud->points[i].normal_y *= -1.0f;
00895                                                 cloud->points[i].normal_z *= -1.0f;
00896                                         }
00897                                 }
00898                                 else
00899                                 {
00900                                         UWARN("Not found camera viewpoint for point %d", i);
00901                                 }
00902                         }
00903                 }
00904         }
00905 }
00906 
00907 pcl::PolygonMesh::Ptr meshDecimation(const pcl::PolygonMesh::Ptr & mesh, float factor)
00908 {
00909         pcl::PolygonMesh::Ptr output(new pcl::PolygonMesh);
00910 #ifndef DISABLE_VTK
00911         pcl::MeshQuadricDecimationVTK mqd;
00912         mqd.setTargetReductionFactor(factor);
00913         mqd.setInputMesh(mesh);
00914         mqd.process (*output);
00915 #else
00916         UWARN("RTAB-Map is not built with VTK module so mesh decimation cannot be used!");
00917         *output = *mesh;
00918 #endif
00919         return output;
00920 }
00921 
00922 }
00923 
00924 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:28