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 <set>
00041 
00042 namespace rtabmap
00043 {
00044 
00045 namespace util3d
00046 {
00047 
00057 void RTABMAP_EXP createPolygonIndexes(
00058                 const std::vector<pcl::Vertices> & polygons,
00059                 int cloudSize,
00060                 std::vector<std::set<int> > & neighborPolygons,
00061                 std::vector<std::set<int> > & vertexPolygons);
00062 
00063 std::vector<pcl::Vertices> RTABMAP_EXP organizedFastMesh(
00064                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00065                 double angleTolerance = M_PI/16,
00066                 bool quad=true,
00067                 int trianglePixelSize = 2,
00068                 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
00069 std::vector<pcl::Vertices> RTABMAP_EXP organizedFastMesh(
00070                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00071                 double angleTolerance = M_PI/16,
00072                 bool quad=true,
00073                 int trianglePixelSize = 2,
00074                 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
00075 
00076 void RTABMAP_EXP appendMesh(
00077                 pcl::PointCloud<pcl::PointXYZRGBNormal> & cloudA,
00078                 std::vector<pcl::Vertices> & polygonsA,
00079                 const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloudB,
00080                 const std::vector<pcl::Vertices> & polygonsB);
00081 void RTABMAP_EXP appendMesh(
00082                 pcl::PointCloud<pcl::PointXYZRGB> & cloudA,
00083                 std::vector<pcl::Vertices> & polygonsA,
00084                 const pcl::PointCloud<pcl::PointXYZRGB> & cloudB,
00085                 const std::vector<pcl::Vertices> & polygonsB);
00086 
00087 // return map from new to old polygon indices
00088 std::map<int, int> RTABMAP_EXP filterNotUsedVerticesFromMesh(
00089                 const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
00090                 const std::vector<pcl::Vertices> & polygons,
00091                 pcl::PointCloud<pcl::PointXYZRGBNormal> & outputCloud,
00092                 std::vector<pcl::Vertices> & outputPolygons);
00093 std::map<int, int> RTABMAP_EXP filterNotUsedVerticesFromMesh(
00094                 const pcl::PointCloud<pcl::PointXYZRGB> & cloud,
00095                 const std::vector<pcl::Vertices> & polygons,
00096                 pcl::PointCloud<pcl::PointXYZRGB> & outputCloud,
00097                 std::vector<pcl::Vertices> & outputPolygons);
00098 
00099 std::vector<pcl::Vertices> RTABMAP_EXP filterCloseVerticesFromMesh(
00100                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud,
00101                 const std::vector<pcl::Vertices> & polygons,
00102                 float radius,
00103                 float angle,
00104                 bool keepLatestInRadius);
00105 
00106 std::vector<pcl::Vertices> RTABMAP_EXP filterInvalidPolygons(
00107                 const std::vector<pcl::Vertices> & polygons);
00108 
00109 pcl::PolygonMesh::Ptr RTABMAP_EXP createMesh(
00110                 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloudWithNormals,
00111                 float gp3SearchRadius = 0.025,
00112                 float gp3Mu = 2.5,
00113                 int gp3MaximumNearestNeighbors = 100,
00114                 float gp3MaximumSurfaceAngle = M_PI/4,
00115                 float gp3MinimumAngle = M_PI/18,
00116                 float gp3MaximumAngle = 2*M_PI/3,
00117                 bool gp3NormalConsistency = true);
00118 
00119 pcl::TextureMesh::Ptr RTABMAP_EXP createTextureMesh(
00120                 const pcl::PolygonMesh::Ptr & mesh,
00121                 const std::map<int, Transform> & poses,
00122                 const std::map<int, CameraModel> & cameraModels,
00123                 const std::map<int, cv::Mat> & images,
00124                 const std::string & tmpDirectory = ".",
00125                 int kNormalSearch = 20); // if mesh doesn't have normals, compute them with k neighbors
00126 
00127 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
00128                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00129                 int normalKSearch = 20,
00130                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00131 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
00132                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00133                 int normalKSearch = 20,
00134                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00135 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
00136                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00137                 const pcl::IndicesPtr & indices,
00138                 int normalKSearch = 20,
00139                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00140 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
00141                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00142                 const pcl::IndicesPtr & indices,
00143                 int normalKSearch = 20,
00144                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00145 
00146 pcl::PointCloud<pcl::Normal>::Ptr computeFastOrganizedNormals(
00147                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00148                 float maxDepthChangeFactor = 0.02f,
00149                 float normalSmoothingSize = 10.0f,
00150                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00151 pcl::PointCloud<pcl::Normal>::Ptr computeFastOrganizedNormals(
00152                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00153                 const pcl::IndicesPtr & indices,
00154                 float maxDepthChangeFactor = 0.02f,
00155                 float normalSmoothingSize = 10.0f,
00156                 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
00157 
00158 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP mls(
00159                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00160                 float searchRadius = 0.0f,
00161                 int polygonialOrder = 2,
00162                 int upsamplingMethod = 0, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
00163                 float upsamplingRadius = 0.0f,   // SAMPLE_LOCAL_PLANE
00164                 float upsamplingStep = 0.0f,     // SAMPLE_LOCAL_PLANE
00165                 int pointDensity = 0,            // RANDOM_UNIFORM_DENSITY
00166                 float dilationVoxelSize = 1.0f,  // VOXEL_GRID_DILATION
00167                 int dilationIterations = 0);     // VOXEL_GRID_DILATION
00168 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP mls(
00169                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00170                 const pcl::IndicesPtr & indices,
00171                 float searchRadius = 0.0f,
00172                 int polygonialOrder = 2,
00173                 int upsamplingMethod = 0, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
00174                 float upsamplingRadius = 0.0f,   // SAMPLE_LOCAL_PLANE
00175                 float upsamplingStep = 0.0f,     // SAMPLE_LOCAL_PLANE
00176                 int pointDensity = 0,            // RANDOM_UNIFORM_DENSITY
00177                 float dilationVoxelSize = 1.0f,  // VOXEL_GRID_DILATION
00178                 int dilationIterations = 0);     // VOXEL_GRID_DILATION
00179 
00180 void RTABMAP_EXP adjustNormalsToViewPoints(
00181                 const std::map<int, Transform> & poses,
00182                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
00183                 const std::vector<int> & rawCameraIndices,
00184                 pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
00185 void RTABMAP_EXP adjustNormalsToViewPoints(
00186                 const std::map<int, Transform> & poses,
00187                 const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
00188                 const std::vector<int> & rawCameraIndices,
00189                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
00190 
00191 pcl::PolygonMesh::Ptr RTABMAP_EXP meshDecimation(const pcl::PolygonMesh::Ptr & mesh, float factor);
00192 
00193 template<typename pointT>
00194 std::vector<pcl::Vertices> normalizePolygonsSide(
00195                 const pcl::PointCloud<pointT> & cloud,
00196                 const std::vector<pcl::Vertices> & polygons,
00197                 const pcl::PointXYZ & viewPoint = pcl::PointXYZ(0,0,0))
00198 {
00199         std::vector<pcl::Vertices> output(polygons.size());
00200         for(unsigned int i=0; i<polygons.size(); ++i)
00201         {
00202                 pcl::Vertices polygon = polygons[i];
00203                 Eigen::Vector3f v1 = cloud.at(polygon.vertices[1]).getVector3fMap() - cloud.at(polygon.vertices[0]).getVector3fMap();
00204                 Eigen::Vector3f v2 = cloud.at(polygon.vertices[2]).getVector3fMap() - cloud.at(polygon.vertices[0]).getVector3fMap();
00205                 Eigen::Vector3f n = (v1.cross(v2)).normalized();
00206 
00207                 Eigen::Vector3f p = Eigen::Vector3f(viewPoint.x, viewPoint.y, viewPoint.z) - cloud.at(polygon.vertices[1]).getVector3fMap();
00208 
00209                 float result = n.dot(p);
00210                 if(result < 0)
00211                 {
00212                         //reverse vertices order
00213                         int tmp = polygon.vertices[0];
00214                         polygon.vertices[0] = polygon.vertices[2];
00215                         polygon.vertices[2] = tmp;
00216                 }
00217 
00218                 output[i] = polygon;
00219         }
00220         return output;
00221 }
00222 
00223 } // namespace util3d
00224 } // namespace rtabmap
00225 
00226 #endif /* UTIL3D_SURFACE_H_ */


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