Showing
8 changed files
with
815 additions
and
0 deletions
mesh_modeling/CMakeLists.txt
0 → 100644
| 1 | +cmake_minimum_required(VERSION 2.8 FATAL_ERROR) | ||
| 2 | + | ||
| 3 | +project(Capstone) | ||
| 4 | +set(CMAKE_BUILD_TYPE Release) | ||
| 5 | +add_compile_options(-std=c++11) | ||
| 6 | + | ||
| 7 | +find_package(PCL 1.7 REQUIRED) | ||
| 8 | +find_package(Eigen3 REQUIRED) | ||
| 9 | +find_package(OpenCV REQUIRED) | ||
| 10 | +find_package(Boost COMPONENTS program_options filesystem REQUIRED) | ||
| 11 | + | ||
| 12 | +include_directories( | ||
| 13 | + include | ||
| 14 | + ${Boost_INCLUDE_DIRS} | ||
| 15 | + ${PCL_INCLUDE_DIRS} | ||
| 16 | + ${EIGEN3_INCLUDE_DIR} | ||
| 17 | +) | ||
| 18 | + | ||
| 19 | +set(sources | ||
| 20 | +) | ||
| 21 | + | ||
| 22 | +link_directories(${PCL_LIBRARY_DIRS}) | ||
| 23 | +add_definitions(${PCL_DEFINITIONS}) | ||
| 24 | + | ||
| 25 | +add_executable(cloud src/pointcloud.cpp ${sources}) | ||
| 26 | +target_link_libraries(cloud ${PCL_LIBRARIES} ${OpenCV_LIBS} ${Boost_LIBRARIES}) | ||
| 27 | + | ||
| 28 | +add_executable(mesh src/mesh.cpp ${sources}) | ||
| 29 | +target_link_libraries(mesh ${PCL_LIBRARIES} ${OpenCV_LIBS}) | ||
| 30 | + | ||
| 31 | +add_executable(obj src/obj.cpp ${sources}) | ||
| 32 | +target_link_libraries(obj ${PCL_LIBRARIES} ${OpenCV_LIBS}) | ||
| 33 | + | ||
| 34 | +add_executable(densedepth src/densedepth.cpp ${sources}) | ||
| 35 | +target_link_libraries(densedepth ${PCL_LIBRARIES} ${OpenCV_LIBS}) |
mesh_modeling/include/common.h
0 → 100644
| 1 | +#pragma once | ||
| 2 | + | ||
| 3 | +//common | ||
| 4 | +#include <string> | ||
| 5 | +#include <fstream> | ||
| 6 | +#include <iostream> | ||
| 7 | +#include <vector> | ||
| 8 | +#include <ctime> | ||
| 9 | +#include <cstdio> | ||
| 10 | +#include <algorithm> | ||
| 11 | +#include <stdlib.h> | ||
| 12 | +#include <sstream> | ||
| 13 | +#include <iomanip> | ||
| 14 | + | ||
| 15 | +//eigen | ||
| 16 | +#include <Eigen/Dense> | ||
| 17 | + | ||
| 18 | +//boost | ||
| 19 | +#include <boost/format.hpp> | ||
| 20 | +#include <boost/filesystem.hpp> | ||
| 21 | +#include <boost/thread/thread.hpp> | ||
| 22 | +#include <boost/algorithm/string.hpp> | ||
| 23 | + | ||
| 24 | +//opencv | ||
| 25 | +#include <opencv2/core.hpp> | ||
| 26 | +#include <opencv2/highgui.hpp> | ||
| 27 | +#include <opencv2/imgproc.hpp> | ||
| 28 | + | ||
| 29 | +//pcl | ||
| 30 | +#include <pcl/point_types.h> | ||
| 31 | +#include <pcl/point_cloud.h> | ||
| 32 | +#include <pcl/io/io.h> | ||
| 33 | +#include <pcl/io/pcd_io.h> | ||
| 34 | +#include <pcl/io/vtk_io.h> | ||
| 35 | +#include <pcl/io/vtk_lib_io.h> | ||
| 36 | +#include <pcl/kdtree/kdtree_flann.h> | ||
| 37 | +#include <pcl/filters/filter.h> | ||
| 38 | +#include <pcl/filters/radius_outlier_removal.h> | ||
| 39 | +#include <pcl/filters/voxel_grid.h> | ||
| 40 | +#include <pcl/features/normal_3d.h> | ||
| 41 | +#include <pcl/surface/mls.h> | ||
| 42 | +#include <pcl/surface/poisson.h> | ||
| 43 | +#include <pcl/surface/marching_cubes_hoppe.h> | ||
| 44 | +#include <pcl/surface/gp3.h> | ||
| 45 | + | ||
| 46 | +using namespace boost::filesystem; | ||
| 47 | + | ||
| 48 | +struct camInfo | ||
| 49 | +{ | ||
| 50 | + double fx; | ||
| 51 | + double fy; | ||
| 52 | + double cx; | ||
| 53 | + double cy; | ||
| 54 | + double k1; | ||
| 55 | + double k2; | ||
| 56 | + double p1; | ||
| 57 | + double p2; | ||
| 58 | + int width; | ||
| 59 | + int height; | ||
| 60 | +}; | ||
| 61 | + | ||
| 62 | +void realsenseSetUp(camInfo& cam) | ||
| 63 | +{ | ||
| 64 | + cam.fx = 612.1810302745375; | ||
| 65 | + cam.fy = 612.27685546875; | ||
| 66 | + cam.cx = 323.64208984375; | ||
| 67 | + cam.cy = 234.55838012695312; | ||
| 68 | + cam.k1 = 0; | ||
| 69 | + cam.k2 = 0; | ||
| 70 | + cam.p1 = 0; | ||
| 71 | + cam.p2 = 0; | ||
| 72 | + cam.width = 640; | ||
| 73 | + cam.height = 480; | ||
| 74 | +} | ||
| 75 | + | ||
| 76 | +Eigen::Vector3d coordinateRotation(double x, double y, double z) | ||
| 77 | +{ | ||
| 78 | + Eigen::Vector3d coord; | ||
| 79 | + coord << x, y, z; | ||
| 80 | + | ||
| 81 | + Eigen::Matrix3d rot; | ||
| 82 | + rot << 1, 0, 0, 0, 0, 1, 0, -1, 0; | ||
| 83 | + | ||
| 84 | + coord = rot * coord; | ||
| 85 | + return coord; | ||
| 86 | +} | ||
| ... | \ No newline at end of file | ... | \ No newline at end of file |
mesh_modeling/include/cv_func.h
0 → 100644
| 1 | +#pragma once | ||
| 2 | +#include "common.h" | ||
| 3 | + | ||
| 4 | +void readFolder(std::string folderPath, std::vector<cv::Mat>& depths) | ||
| 5 | +{ | ||
| 6 | + path p(folderPath); | ||
| 7 | + try | ||
| 8 | + { | ||
| 9 | + if(exists(p) && is_directory(p)) | ||
| 10 | + { | ||
| 11 | + std::vector<std::string> imgs; | ||
| 12 | + for(directory_entry& x : directory_iterator(p)) | ||
| 13 | + { | ||
| 14 | + std::string img = x.path().string(); | ||
| 15 | + imgs.push_back(img); | ||
| 16 | + } | ||
| 17 | + std::sort(imgs.begin(), imgs.end()); | ||
| 18 | + | ||
| 19 | + for(auto img : imgs) | ||
| 20 | + { | ||
| 21 | + cv::Mat depth = cv::imread(img, cv::IMREAD_ANYDEPTH); //16UC1 | ||
| 22 | + depths.push_back(depth); | ||
| 23 | + } | ||
| 24 | + } | ||
| 25 | + else | ||
| 26 | + { | ||
| 27 | + std::cout << "[Error] Check Depth Map Folder Path" << std::endl; | ||
| 28 | + exit(0); | ||
| 29 | + } | ||
| 30 | + } | ||
| 31 | + catch(const filesystem_error& ex) | ||
| 32 | + { | ||
| 33 | + std::cout << ex.what() << std::endl; | ||
| 34 | + } | ||
| 35 | +} | ||
| 36 | + | ||
| 37 | +std::string type2str(int type) | ||
| 38 | +{ | ||
| 39 | + std::string r; | ||
| 40 | + | ||
| 41 | + uchar depth = type & CV_MAT_DEPTH_MASK; | ||
| 42 | + uchar chans = 1 + (type >> CV_CN_SHIFT); | ||
| 43 | + | ||
| 44 | + switch ( depth ) | ||
| 45 | + { | ||
| 46 | + case CV_8U: r = "8U"; break; | ||
| 47 | + case CV_8S: r = "8S"; break; | ||
| 48 | + case CV_16U: r = "16U"; break; | ||
| 49 | + case CV_16S: r = "16S"; break; | ||
| 50 | + case CV_32S: r = "32S"; break; | ||
| 51 | + case CV_32F: r = "32F"; break; | ||
| 52 | + case CV_64F: r = "64F"; break; | ||
| 53 | + default: r = "User"; break; | ||
| 54 | + } | ||
| 55 | + | ||
| 56 | + r += "C"; | ||
| 57 | + r += (chans+'0'); | ||
| 58 | + | ||
| 59 | + return r; | ||
| 60 | +} | ||
| 61 | + | ||
| 62 | +cv::Mat getMeanImg(std::vector<cv::Mat> depths) | ||
| 63 | +{ | ||
| 64 | + if(depths.empty()) | ||
| 65 | + { | ||
| 66 | + std::cout << "[Error] no input images" << std::endl; | ||
| 67 | + exit(0); | ||
| 68 | + } | ||
| 69 | + | ||
| 70 | + cv::Mat m(depths[0].rows, depths[0].cols, CV_64FC1); | ||
| 71 | + m.setTo(0); | ||
| 72 | + | ||
| 73 | + cv::Mat tmp; | ||
| 74 | + for(auto depth : depths) | ||
| 75 | + { | ||
| 76 | + depth.convertTo(tmp, CV_64FC1); | ||
| 77 | + m += tmp; | ||
| 78 | + } | ||
| 79 | + | ||
| 80 | + m.convertTo(m, CV_16UC1, 1.0 / depths.size()); | ||
| 81 | + return m; | ||
| 82 | +} | ||
| 83 | + | ||
| 84 | +cv::Mat medianFilter(cv::Mat img) | ||
| 85 | +{ | ||
| 86 | + cv::Mat filtered; | ||
| 87 | + cv::medianBlur(img, filtered, 5); | ||
| 88 | + return filtered; | ||
| 89 | +} | ||
| 90 | + | ||
| 91 | +void reconstruction3D(camInfo cam, cv::Mat img, pcl::PointCloud<pcl::PointXYZ>::Ptr cloud) | ||
| 92 | +{ | ||
| 93 | + for(int i = 0; i < img.cols; i++) | ||
| 94 | + { | ||
| 95 | + for(int j = 0; j < img.rows; j++) | ||
| 96 | + { | ||
| 97 | + auto d = img.at<u_int16_t>(j, i) / 1000.0; | ||
| 98 | + if(d < 0.105 || d > 3.0) | ||
| 99 | + { //realsense min dist && max dist | ||
| 100 | + continue; | ||
| 101 | + } | ||
| 102 | + double x = (i - cam.cx) * d / cam.fx; | ||
| 103 | + double y = (j - cam.cy) * d / cam.fy; | ||
| 104 | + double z = d; | ||
| 105 | + | ||
| 106 | + pcl::PointXYZ pt; | ||
| 107 | + pt.x = x; | ||
| 108 | + pt.y = y; | ||
| 109 | + pt.z = z; | ||
| 110 | + cloud->push_back(pt); | ||
| 111 | + } | ||
| 112 | + } | ||
| 113 | +} | ||
| ... | \ No newline at end of file | ... | \ No newline at end of file |
mesh_modeling/include/pcl_func.h
0 → 100644
| 1 | +#pragma once | ||
| 2 | +#include "common.h" | ||
| 3 | + | ||
| 4 | +void noise_removal(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud) | ||
| 5 | +{ | ||
| 6 | + if(cloud->size() == 0) | ||
| 7 | + { | ||
| 8 | + std::cout << "[Error] pointcloud empty" << std::endl; | ||
| 9 | + return; | ||
| 10 | + } | ||
| 11 | + | ||
| 12 | + const double r = 0.1; | ||
| 13 | + const int min_neighbor = 50; | ||
| 14 | + | ||
| 15 | + pcl::RadiusOutlierRemoval<pcl::PointXYZ> outrem; | ||
| 16 | + outrem.setInputCloud(cloud); | ||
| 17 | + outrem.setRadiusSearch(r); | ||
| 18 | + outrem.setMinNeighborsInRadius(min_neighbor); | ||
| 19 | + outrem.filter(*cloud); | ||
| 20 | + | ||
| 21 | + std::cout << "pointcloud filtered..." << std::endl; | ||
| 22 | +} | ||
| 23 | + | ||
| 24 | +void downsampling(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud) | ||
| 25 | +{ | ||
| 26 | + if(cloud->size() == 0) | ||
| 27 | + { | ||
| 28 | + std::cout << "[Error] pointcloud empty" << std::endl; | ||
| 29 | + return; | ||
| 30 | + } | ||
| 31 | + | ||
| 32 | + const double leaf = 0.05; | ||
| 33 | + | ||
| 34 | + pcl::VoxelGrid<pcl::PointXYZ> grid; | ||
| 35 | + grid.setLeafSize(leaf, leaf, leaf); | ||
| 36 | + grid.setInputCloud(cloud); | ||
| 37 | + grid.filter(*cloud); | ||
| 38 | + | ||
| 39 | + std::cout << "pointcloud downsampled..." << std::endl; | ||
| 40 | +} | ||
| 41 | + | ||
| 42 | +void upsampling(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud) | ||
| 43 | +{ | ||
| 44 | + //mls upsampling | ||
| 45 | + pcl::PointCloud<pcl::PointNormal>::Ptr tmp(new pcl::PointCloud<pcl::PointNormal>); | ||
| 46 | + pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>); | ||
| 47 | + pcl::MovingLeastSquares<pcl::PointXYZ, pcl::PointNormal> mls; | ||
| 48 | + | ||
| 49 | + mls.setComputeNormals(true); | ||
| 50 | + | ||
| 51 | + mls.setInputCloud(cloud); | ||
| 52 | + mls.setPolynomialOrder(2); | ||
| 53 | + mls.setSearchMethod(tree); | ||
| 54 | + mls.setSearchRadius(0.03); | ||
| 55 | + | ||
| 56 | + mls.process(*tmp); | ||
| 57 | + | ||
| 58 | + pcl::PointCloud<pcl::PointXYZ>::Ptr filter(new pcl::PointCloud<pcl::PointXYZ>); | ||
| 59 | + cloud->clear(); | ||
| 60 | + pcl::copyPointCloud(*tmp, *filter); | ||
| 61 | + | ||
| 62 | + std::vector<int> idx; | ||
| 63 | + pcl::removeNaNFromPointCloud(*filter, *cloud, idx); //not working | ||
| 64 | +} | ||
| 65 | + | ||
| 66 | +void normal_estimation(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals) | ||
| 67 | +{ | ||
| 68 | + pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> n; | ||
| 69 | + pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>); | ||
| 70 | + pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>); | ||
| 71 | + | ||
| 72 | + tree->setInputCloud(cloud); | ||
| 73 | + n.setInputCloud(cloud); | ||
| 74 | + n.setSearchMethod(tree); | ||
| 75 | + n.setKSearch(30); | ||
| 76 | + n.compute(*normals); | ||
| 77 | + | ||
| 78 | + pcl::concatenateFields(*cloud, *normals, *cloud_with_normals); | ||
| 79 | +} | ||
| 80 | + | ||
| 81 | +void triangulation(pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals, pcl::PolygonMesh& triangles) | ||
| 82 | +{ | ||
| 83 | + pcl::GreedyProjectionTriangulation<pcl::PointNormal> gp; | ||
| 84 | + | ||
| 85 | + pcl::search::KdTree<pcl::PointNormal>::Ptr tree_normal(new pcl::search::KdTree<pcl::PointNormal>); | ||
| 86 | + tree_normal->setInputCloud(cloud_with_normals); | ||
| 87 | + | ||
| 88 | + gp.setSearchRadius(0.025); | ||
| 89 | + gp.setMu(2.5); | ||
| 90 | + gp.setMaximumNearestNeighbors(200); | ||
| 91 | + gp.setMaximumSurfaceAngle(M_PI/4); // 45 degrees | ||
| 92 | + gp.setMaximumAngle(2*M_PI/3); // 120 degrees | ||
| 93 | + gp.setMinimumAngle(M_PI/18); // 10 degrees | ||
| 94 | + gp.setNormalConsistency(false); | ||
| 95 | + gp.setConsistentVertexOrdering(true); | ||
| 96 | + gp.setInputCloud(cloud_with_normals); | ||
| 97 | + gp.setSearchMethod(tree_normal); | ||
| 98 | + gp.reconstruct(triangles); | ||
| 99 | +} | ||
| 100 | + | ||
| 101 | +int saveOBJFile (const std::string &file_name, const pcl::TextureMesh &tex_mesh, unsigned precision, | ||
| 102 | + pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, camInfo cam) | ||
| 103 | +{ | ||
| 104 | + if (tex_mesh.cloud.data.empty ()) | ||
| 105 | + { | ||
| 106 | + PCL_ERROR ("[pcl::io::saveOBJFile] Input point cloud has no data!\n"); | ||
| 107 | + return (-1); | ||
| 108 | + } | ||
| 109 | + | ||
| 110 | + //Open file | ||
| 111 | + std::ofstream fs; | ||
| 112 | + fs.precision(precision); | ||
| 113 | + fs.open(file_name.c_str()); | ||
| 114 | + | ||
| 115 | + //Define material file | ||
| 116 | + std::string mtl_file_name = file_name.substr(0, file_name.find_last_of ('.')) + ".mtl"; | ||
| 117 | + //Strip path for "mtllib" command | ||
| 118 | + std::string mtl_file_name_nopath = mtl_file_name; | ||
| 119 | + mtl_file_name_nopath.erase(0, mtl_file_name.find_last_of ('/') + 1); | ||
| 120 | + | ||
| 121 | + /* Write 3D information */ | ||
| 122 | + //number of points | ||
| 123 | + int nr_points = tex_mesh.cloud.width * tex_mesh.cloud.height; | ||
| 124 | + int point_size = tex_mesh.cloud.data.size () / nr_points; | ||
| 125 | + | ||
| 126 | + //number of meshes | ||
| 127 | + int nr_meshes = tex_mesh.tex_polygons.size (); | ||
| 128 | + | ||
| 129 | + //number of faces for header | ||
| 130 | + int nr_faces = 0; | ||
| 131 | + for (int m = 0; m < nr_meshes; ++m) | ||
| 132 | + nr_faces += tex_mesh.tex_polygons[m].size (); | ||
| 133 | + | ||
| 134 | + // Write the header information | ||
| 135 | + fs << "####" << std::endl; | ||
| 136 | + fs << "# OBJ dataFile simple version. File name: " << file_name << std::endl; | ||
| 137 | + fs << "# Vertices: " << nr_points << std::endl; | ||
| 138 | + fs << "# Faces: " << nr_faces << std::endl; | ||
| 139 | + fs << "# Material information:" << std::endl; | ||
| 140 | + fs << "mtllib " << mtl_file_name_nopath << std::endl; | ||
| 141 | + fs << "####" << std::endl; | ||
| 142 | + | ||
| 143 | + // Write vertex coordinates | ||
| 144 | + PCL_INFO ("Writing vertices...\n"); | ||
| 145 | + fs << "# Vertices" << std::endl; | ||
| 146 | + for (int i = 0; i < nr_points; ++i) | ||
| 147 | + { | ||
| 148 | + int xyz = 0; | ||
| 149 | + // "v" just be written one | ||
| 150 | + bool v_written = false; | ||
| 151 | + for (std::size_t d = 0; d < tex_mesh.cloud.fields.size (); ++d) | ||
| 152 | + { | ||
| 153 | + // adding vertex | ||
| 154 | + if ((tex_mesh.cloud.fields[d].datatype == pcl::PCLPointField::FLOAT32) && ( | ||
| 155 | + tex_mesh.cloud.fields[d].name == "x" || | ||
| 156 | + tex_mesh.cloud.fields[d].name == "y" || | ||
| 157 | + tex_mesh.cloud.fields[d].name == "z")) | ||
| 158 | + { | ||
| 159 | + if (!v_written) | ||
| 160 | + { | ||
| 161 | + // write vertices beginning with v | ||
| 162 | + fs << "v "; | ||
| 163 | + v_written = true; | ||
| 164 | + } | ||
| 165 | + float value; | ||
| 166 | + memcpy (&value, &tex_mesh.cloud.data[i * point_size + tex_mesh.cloud.fields[d].offset], sizeof (float)); | ||
| 167 | + fs << value; | ||
| 168 | + if (++xyz == 3) | ||
| 169 | + break; | ||
| 170 | + fs << " "; | ||
| 171 | + } | ||
| 172 | + } | ||
| 173 | + if (xyz != 3) | ||
| 174 | + { | ||
| 175 | + PCL_ERROR ("[pcl::io::saveOBJFile] Input point cloud has no XYZ data!\n"); | ||
| 176 | + return (-2); | ||
| 177 | + } | ||
| 178 | + fs << std::endl; | ||
| 179 | + } | ||
| 180 | + fs << "# "<< nr_points <<" vertices" << std::endl; | ||
| 181 | + | ||
| 182 | + // Write vertex texture | ||
| 183 | + PCL_INFO ("Writing textures...\n"); | ||
| 184 | + fs << "# " << cloud->size() << " vertex textures in mesh " << std::endl; | ||
| 185 | + for (int i = 0; i < cloud->size(); ++i) | ||
| 186 | + { | ||
| 187 | + auto pt = cloud->at(i); | ||
| 188 | + fs << "vt "; | ||
| 189 | + fs << (pt.x * cam.fx / pt.z + cam.cx) / cam.width << " "; | ||
| 190 | + fs << 1.0 - ((pt.y * cam.fy / pt.z + cam.cy) / cam.height) << std::endl; | ||
| 191 | + } | ||
| 192 | + | ||
| 193 | + // Write vertex normals | ||
| 194 | + PCL_INFO ("Writing normals...\n"); | ||
| 195 | + for (int i = 0; i < nr_points; ++i) | ||
| 196 | + { | ||
| 197 | + int xyz = 0; | ||
| 198 | + // "vn" just be written one | ||
| 199 | + bool v_written = false; | ||
| 200 | + for (std::size_t d = 0; d < tex_mesh.cloud.fields.size (); ++d) | ||
| 201 | + { | ||
| 202 | + // adding vertex | ||
| 203 | + if ((tex_mesh.cloud.fields[d].datatype == pcl::PCLPointField::FLOAT32) && ( | ||
| 204 | + tex_mesh.cloud.fields[d].name == "normal_x" || | ||
| 205 | + tex_mesh.cloud.fields[d].name == "normal_y" || | ||
| 206 | + tex_mesh.cloud.fields[d].name == "normal_z")) | ||
| 207 | + { | ||
| 208 | + if (!v_written) | ||
| 209 | + { | ||
| 210 | + // write vertices beginning with vn | ||
| 211 | + fs << "vn "; | ||
| 212 | + v_written = true; | ||
| 213 | + } | ||
| 214 | + float value; | ||
| 215 | + memcpy (&value, &tex_mesh.cloud.data[i * point_size + tex_mesh.cloud.fields[d].offset], sizeof (float)); | ||
| 216 | + fs << value; | ||
| 217 | + if (++xyz == 3) | ||
| 218 | + break; | ||
| 219 | + fs << " "; | ||
| 220 | + } | ||
| 221 | + } | ||
| 222 | + if (xyz != 3) | ||
| 223 | + { | ||
| 224 | + PCL_ERROR ("[pcl::io::saveOBJFile] Input point cloud has no normals!\n"); | ||
| 225 | + return (-2); | ||
| 226 | + } | ||
| 227 | + fs << std::endl; | ||
| 228 | + } | ||
| 229 | + | ||
| 230 | + PCL_INFO ("Writing faces...\n"); | ||
| 231 | + int f_idx = 0; | ||
| 232 | + for (int m = 0; m < nr_meshes; ++m) | ||
| 233 | + { | ||
| 234 | + if (m > 0) | ||
| 235 | + f_idx += tex_mesh.tex_polygons[m-1].size (); | ||
| 236 | + | ||
| 237 | + if(!tex_mesh.tex_materials.empty ()) | ||
| 238 | + { | ||
| 239 | + fs << "# The material will be used for mesh " << m << std::endl; | ||
| 240 | + //TODO pbl here with multi texture and unseen faces | ||
| 241 | + fs << "usemtl " << tex_mesh.tex_materials[m].tex_name << std::endl; | ||
| 242 | + fs << "# Faces" << std::endl; | ||
| 243 | + } | ||
| 244 | + for (std::size_t i = 0; i < tex_mesh.tex_polygons[m].size(); ++i) | ||
| 245 | + { | ||
| 246 | + // Write faces with "f" | ||
| 247 | + fs << "f"; | ||
| 248 | + // There's one UV per vertex per face, i.e., the same vertex can have | ||
| 249 | + // different UV depending on the face. | ||
| 250 | + for (std::size_t j = 0; j < tex_mesh.tex_polygons[m][i].vertices.size (); ++j) | ||
| 251 | + { | ||
| 252 | + unsigned int idx = tex_mesh.tex_polygons[m][i].vertices[j] + 1; | ||
| 253 | + fs << " " << idx | ||
| 254 | + << "/" << idx | ||
| 255 | + << "/" << idx; // vertex index in obj file format starting with 1 | ||
| 256 | + } | ||
| 257 | + fs << std::endl; | ||
| 258 | + } | ||
| 259 | + //PCL_INFO ("%d faces in mesh %d \n", tex_mesh.tex_polygons[m].size () , m); | ||
| 260 | + fs << "# "<< tex_mesh.tex_polygons[m].size() << " faces in mesh " << m << std::endl; | ||
| 261 | + } | ||
| 262 | + fs << "# End of File"; | ||
| 263 | + | ||
| 264 | + // Close obj file | ||
| 265 | + PCL_INFO ("Closing obj file\n"); | ||
| 266 | + fs.close (); | ||
| 267 | + | ||
| 268 | + /* Write material definition for OBJ file*/ | ||
| 269 | + // Open file | ||
| 270 | + PCL_INFO ("Writing material files\n"); | ||
| 271 | + //don't do it if no material to write | ||
| 272 | + if(tex_mesh.tex_materials.empty ()) | ||
| 273 | + return (0); | ||
| 274 | + | ||
| 275 | + std::ofstream m_fs; | ||
| 276 | + m_fs.precision(precision); | ||
| 277 | + m_fs.open(mtl_file_name.c_str ()); | ||
| 278 | + | ||
| 279 | + //default | ||
| 280 | + m_fs << "#" << std::endl; | ||
| 281 | + m_fs << "# Wavefront material file" << std::endl; | ||
| 282 | + m_fs << "#" << std::endl; | ||
| 283 | + for(int m = 0; m < nr_meshes; ++m) | ||
| 284 | + { | ||
| 285 | + m_fs << "newmtl " << tex_mesh.tex_materials[m].tex_name << std::endl; | ||
| 286 | + m_fs << "Ka "<< tex_mesh.tex_materials[m].tex_Ka.r << " " << tex_mesh.tex_materials[m].tex_Ka.g << " " << tex_mesh.tex_materials[m].tex_Ka.b << std::endl; // defines the ambient color of the material to be (r,g,b). | ||
| 287 | + m_fs << "Kd "<< tex_mesh.tex_materials[m].tex_Kd.r << " " << tex_mesh.tex_materials[m].tex_Kd.g << " " << tex_mesh.tex_materials[m].tex_Kd.b << std::endl; // defines the diffuse color of the material to be (r,g,b). | ||
| 288 | + m_fs << "Ks "<< tex_mesh.tex_materials[m].tex_Ks.r << " " << tex_mesh.tex_materials[m].tex_Ks.g << " " << tex_mesh.tex_materials[m].tex_Ks.b << std::endl; // defines the specular color of the material to be (r,g,b). This color shows up in highlights. | ||
| 289 | + m_fs << "d " << tex_mesh.tex_materials[m].tex_d << std::endl; // defines the transparency of the material to be alpha. | ||
| 290 | + m_fs << "Ns "<< tex_mesh.tex_materials[m].tex_Ns << std::endl; // defines the shininess of the material to be s. | ||
| 291 | + m_fs << "illum "<< tex_mesh.tex_materials[m].tex_illum << std::endl; // denotes the illumination model used by the material. | ||
| 292 | + // illum = 1 indicates a flat material with no specular highlights, so the value of Ks is not used. | ||
| 293 | + // illum = 2 denotes the presence of specular highlights, and so a specification for Ks is required. | ||
| 294 | + m_fs << "map_Kd " << tex_mesh.tex_materials[m].tex_file << std::endl; | ||
| 295 | + m_fs << "###" << std::endl; | ||
| 296 | + } | ||
| 297 | + m_fs.close (); | ||
| 298 | + return (0); | ||
| 299 | +} | ||
| ... | \ No newline at end of file | ... | \ No newline at end of file |
mesh_modeling/src/densedepth.cpp
0 → 100644
| 1 | +#include "common.h" | ||
| 2 | +#include "cv_func.h" | ||
| 3 | +#include "pcl_func.h" | ||
| 4 | + | ||
| 5 | +/* | ||
| 6 | +[input] | ||
| 7 | +argc = 2 | ||
| 8 | +argv[0] = program | ||
| 9 | +argv[1] = densedepth.png (320 x 240) | ||
| 10 | + | ||
| 11 | +[output] | ||
| 12 | +interpolated_densedepth.png (640 x 480) | ||
| 13 | +densedepth.pcd | ||
| 14 | +*/ | ||
| 15 | + | ||
| 16 | +int main(int argc, char** argv) | ||
| 17 | +{ | ||
| 18 | + if(argc != 2) | ||
| 19 | + { | ||
| 20 | + std::cout << "[Error] Program Usage: [./densedepth] [densedepth.png]" << std::endl; | ||
| 21 | + return -1; | ||
| 22 | + } | ||
| 23 | + | ||
| 24 | + //intrinsic setup | ||
| 25 | + camInfo cam; | ||
| 26 | + realsenseSetUp(cam); | ||
| 27 | + | ||
| 28 | + cv::Mat img, interpolated_img; | ||
| 29 | + img = cv::imread(argv[1], cv::IMREAD_ANYDEPTH); | ||
| 30 | + //std::cout << type2str(img.type()) << std::endl; -> 16UC1 | ||
| 31 | + | ||
| 32 | + //interpolation to (320, 240) -> (640, 480) | ||
| 33 | + cv::resize(img, interpolated_img, cv::Size(640, 480), cv::INTER_LINEAR); | ||
| 34 | + std::string inputPath = argv[1]; | ||
| 35 | + std::size_t div = inputPath.find_last_of("/\\"); | ||
| 36 | + std::string outputPath = inputPath.substr(0, div + 1); | ||
| 37 | + cv::imwrite(outputPath + "interpolated_densedepth.png", interpolated_img); | ||
| 38 | + | ||
| 39 | + pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>); | ||
| 40 | + | ||
| 41 | + for(int i = 0; i < interpolated_img.cols; i++) | ||
| 42 | + { | ||
| 43 | + for(int j = 0; j < interpolated_img.rows; j++) | ||
| 44 | + { | ||
| 45 | + auto d = (-interpolated_img.at<u_int16_t>(j, i)) / 1000.0; // closer - darker reversed | ||
| 46 | + double x = (i - cam.cx) * d / cam.fx; | ||
| 47 | + double y = (j - cam.cy) * d / cam.fy; | ||
| 48 | + double z = d; | ||
| 49 | + | ||
| 50 | + pcl::PointXYZ pt; | ||
| 51 | + pt.x = x; | ||
| 52 | + pt.y = y; | ||
| 53 | + pt.z = z; | ||
| 54 | + cloud->push_back(pt); | ||
| 55 | + } | ||
| 56 | + } | ||
| 57 | + pcl::io::savePCDFile(outputPath + "densedepth.pcd", *cloud); | ||
| 58 | + | ||
| 59 | + return 0; | ||
| 60 | +} | ||
| ... | \ No newline at end of file | ... | \ No newline at end of file |
mesh_modeling/src/mesh.cpp
0 → 100644
| 1 | +#include "common.h" | ||
| 2 | +#include "cv_func.h" | ||
| 3 | +#include "pcl_func.h" | ||
| 4 | + | ||
| 5 | +/* | ||
| 6 | +[input] | ||
| 7 | +argc = 3 | ||
| 8 | +argv[0] = program | ||
| 9 | +argv[1] = original pointcloud | ||
| 10 | +argv[2] = filtered pointcloud | ||
| 11 | + | ||
| 12 | +[output] | ||
| 13 | +original mesh -> vtk format | ||
| 14 | +filtered mesh -> vtk format | ||
| 15 | +*/ | ||
| 16 | + | ||
| 17 | +int main(int argc, char** argv) | ||
| 18 | +{ | ||
| 19 | + if(argc != 3) | ||
| 20 | + { | ||
| 21 | + std::cout << "[Error] Program Usage: [./mesh] [original_cloud.pcd] [filtered_cloud.pcd]" << std::endl; | ||
| 22 | + return -1; | ||
| 23 | + } | ||
| 24 | + | ||
| 25 | + //save path | ||
| 26 | + std::string inputPath = argv[1]; | ||
| 27 | + std::size_t div = inputPath.find_last_of("/\\"); | ||
| 28 | + std::string outputPath = inputPath.substr(0, div + 1); | ||
| 29 | + | ||
| 30 | + //load pointcloud data | ||
| 31 | + pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_original(new pcl::PointCloud<pcl::PointXYZ>); | ||
| 32 | + pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>); | ||
| 33 | + pcl::io::loadPCDFile(argv[1], *cloud_original); | ||
| 34 | + pcl::io::loadPCDFile(argv[2], *cloud_filtered); | ||
| 35 | + std::cout << "[Processing] reading pointcloud done..." << std::endl; | ||
| 36 | + | ||
| 37 | + //origianl cloud needs upsampling | ||
| 38 | + //(triangulation process impossible for noisy normal estimation) | ||
| 39 | + //upsampling(cloud_original); | ||
| 40 | + //std::cout << "original cloud upsampling done..." << std::endl; | ||
| 41 | + | ||
| 42 | + //normal estimation | ||
| 43 | + pcl::PointCloud<pcl::PointNormal>::Ptr original_with_normals(new pcl::PointCloud<pcl::PointNormal>); | ||
| 44 | + normal_estimation(cloud_original, original_with_normals); | ||
| 45 | + | ||
| 46 | + pcl::PointCloud<pcl::PointNormal>::Ptr filtered_with_normals(new pcl::PointCloud<pcl::PointNormal>); | ||
| 47 | + normal_estimation(cloud_filtered, filtered_with_normals); | ||
| 48 | + std::cout << "[Processing] normal estimation done..." << std::endl; | ||
| 49 | + | ||
| 50 | + //triangulation | ||
| 51 | + pcl::PolygonMesh triangles_original, triangles_filtered; | ||
| 52 | + triangulation(original_with_normals, triangles_original); | ||
| 53 | + triangulation(filtered_with_normals, triangles_filtered); | ||
| 54 | + std::cout << "[Processing] triangulation done..." << std::endl; | ||
| 55 | + | ||
| 56 | + //save output | ||
| 57 | + pcl::io::saveVTKFile(outputPath + "original_mesh.vtk", triangles_original); | ||
| 58 | + pcl::io::saveVTKFile(outputPath + "filtered_mesh.vtk", triangles_filtered); | ||
| 59 | + | ||
| 60 | + return 0; | ||
| 61 | +} | ||
| ... | \ No newline at end of file | ... | \ No newline at end of file |
mesh_modeling/src/obj.cpp
0 → 100644
| 1 | +#include "common.h" | ||
| 2 | +#include "cv_func.h" | ||
| 3 | +#include "pcl_func.h" | ||
| 4 | + | ||
| 5 | +/* | ||
| 6 | +[input] | ||
| 7 | +argc = 3 | ||
| 8 | +argv[0] = program | ||
| 9 | +argv[1] = vtk file | ||
| 10 | +artv[2] = color img | ||
| 11 | + | ||
| 12 | +[output] | ||
| 13 | +obj file | ||
| 14 | +mtl file | ||
| 15 | +*/ | ||
| 16 | + | ||
| 17 | +int main(int argc, char** argv) | ||
| 18 | +{ | ||
| 19 | + if(argc != 3) | ||
| 20 | + { | ||
| 21 | + std::cout << "[Error] Program Usage: [./obj] [mesh.vtk] [color_img.png]" << std::endl; | ||
| 22 | + return -1; | ||
| 23 | + } | ||
| 24 | + | ||
| 25 | + //read vtk file | ||
| 26 | + pcl::PolygonMesh vtk_mesh; | ||
| 27 | + pcl::io::loadPolygonFileVTK(argv[1], vtk_mesh); | ||
| 28 | + | ||
| 29 | + //copy pointcloud from vtk file (vertices) | ||
| 30 | + pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>); | ||
| 31 | + pcl::fromPCLPointCloud2(vtk_mesh.cloud, *cloud); | ||
| 32 | + | ||
| 33 | + //mesh initialization | ||
| 34 | + pcl::TextureMesh mesh; | ||
| 35 | + mesh.cloud = vtk_mesh.cloud; | ||
| 36 | + std::vector<pcl::Vertices> vertices; | ||
| 37 | + | ||
| 38 | + //copy faces from vtk file | ||
| 39 | + vertices.resize(vtk_mesh.polygons.size()); | ||
| 40 | + for(std::size_t i = 0; i < vtk_mesh.polygons.size(); i++) | ||
| 41 | + { | ||
| 42 | + vertices[i] = vtk_mesh.polygons[i]; | ||
| 43 | + } | ||
| 44 | + mesh.tex_polygons.push_back(vertices); | ||
| 45 | + PCL_INFO("Input mesh contains %zu faces and %zu vertices\n", | ||
| 46 | + mesh.tex_polygons[0].size(), | ||
| 47 | + static_cast<std::size_t>(cloud->size())); | ||
| 48 | + PCL_INFO("...Done.\n"); | ||
| 49 | + | ||
| 50 | + //intrinsic setup | ||
| 51 | + camInfo cam; | ||
| 52 | + realsenseSetUp(cam); | ||
| 53 | + | ||
| 54 | + //one material | ||
| 55 | + mesh.tex_materials.resize(1); | ||
| 56 | + | ||
| 57 | + pcl::TexMaterial mesh_material; | ||
| 58 | + mesh_material.tex_name = "texture image"; | ||
| 59 | + std::string color_img = argv[2]; | ||
| 60 | + color_img = color_img.substr(color_img.find_last_of("/\\") + 1); | ||
| 61 | + mesh_material.tex_file = color_img; | ||
| 62 | + | ||
| 63 | + mesh_material.tex_Ka.r = 0.2f; | ||
| 64 | + mesh_material.tex_Ka.g = 0.2f; | ||
| 65 | + mesh_material.tex_Ka.b = 0.2f; | ||
| 66 | + | ||
| 67 | + mesh_material.tex_Kd.r = 0.8f; | ||
| 68 | + mesh_material.tex_Kd.g = 0.8f; | ||
| 69 | + mesh_material.tex_Kd.b = 0.8f; | ||
| 70 | + | ||
| 71 | + mesh_material.tex_Ks.r = 1.0f; | ||
| 72 | + mesh_material.tex_Ks.g = 1.0f; | ||
| 73 | + mesh_material.tex_Ks.b = 1.0f; | ||
| 74 | + | ||
| 75 | + mesh_material.tex_d = 1.0f; | ||
| 76 | + mesh_material.tex_Ns = 75.0f; | ||
| 77 | + mesh_material.tex_illum = 2; | ||
| 78 | + | ||
| 79 | + mesh.tex_materials[0] = mesh_material; | ||
| 80 | + | ||
| 81 | + //normal estimation | ||
| 82 | + PCL_INFO ("\nEstimating normals...\n"); | ||
| 83 | + pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> n; | ||
| 84 | + pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>); | ||
| 85 | + pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>); | ||
| 86 | + tree->setInputCloud(cloud); | ||
| 87 | + n.setInputCloud(cloud); | ||
| 88 | + n.setSearchMethod(tree); | ||
| 89 | + n.setKSearch(20); | ||
| 90 | + n.compute(*normals); | ||
| 91 | + | ||
| 92 | + pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals(new pcl::PointCloud<pcl::PointNormal>); | ||
| 93 | + pcl::concatenateFields(*cloud, *normals, *cloud_with_normals); | ||
| 94 | + pcl::toPCLPointCloud2(*cloud_with_normals, mesh.cloud); | ||
| 95 | + PCL_INFO("...Done.\n"); | ||
| 96 | + | ||
| 97 | + //obj file creating | ||
| 98 | + PCL_INFO("\nSaving mesh to textured_mesh.obj\n"); | ||
| 99 | + saveOBJFile("mesh.obj", mesh, 5, cloud, cam); | ||
| 100 | + | ||
| 101 | + return 0; | ||
| 102 | +} | ||
| ... | \ No newline at end of file | ... | \ No newline at end of file |
mesh_modeling/src/pointcloud.cpp
0 → 100644
| 1 | +#include "common.h" | ||
| 2 | +#include "cv_func.h" | ||
| 3 | +#include "pcl_func.h" | ||
| 4 | + | ||
| 5 | +/* | ||
| 6 | +[input] | ||
| 7 | +argc = 2 | ||
| 8 | +argv[0] = program | ||
| 9 | +argv[1] = depth folder (containing depth images) | ||
| 10 | + | ||
| 11 | +[output] | ||
| 12 | +single frame depth image & point cloud | ||
| 13 | +average depth image & point cloud | ||
| 14 | +*/ | ||
| 15 | + | ||
| 16 | +int main(int argc, char** argv) | ||
| 17 | +{ | ||
| 18 | + if(argc != 2) | ||
| 19 | + { | ||
| 20 | + std::cout << "[Error] Program Usage: [./cloud] [depth image folder]" << std::endl; | ||
| 21 | + return -1; | ||
| 22 | + } | ||
| 23 | + | ||
| 24 | + //intrinsic setup | ||
| 25 | + camInfo cam; | ||
| 26 | + realsenseSetUp(cam); | ||
| 27 | + std::cout << "[Processing] Intrinsic parameters for Realsense setting done..." << std::endl; | ||
| 28 | + | ||
| 29 | + //get raw, filtered img | ||
| 30 | + std::string folderPath = argv[1]; | ||
| 31 | + std::vector<cv::Mat> depths; | ||
| 32 | + readFolder(folderPath, depths); | ||
| 33 | + cv::Mat meanImg = getMeanImg(depths); | ||
| 34 | + cv::Mat filtered = medianFilter(meanImg); | ||
| 35 | + cv::Mat raw = depths[0]; | ||
| 36 | + std::cout << "[Processing] image filtering done..." << std::endl; | ||
| 37 | + | ||
| 38 | + //3D reconstruction | ||
| 39 | + pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_original(new pcl::PointCloud<pcl::PointXYZ>); | ||
| 40 | + pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>); | ||
| 41 | + | ||
| 42 | + reconstruction3D(cam, raw, cloud_original); | ||
| 43 | + reconstruction3D(cam, filtered, cloud_filtered); | ||
| 44 | + std::cout << "[Processing] 3d reconstruction done..." << std::endl; | ||
| 45 | + | ||
| 46 | + //create output folder | ||
| 47 | + std::size_t div = folderPath.find_last_of("/\\"); | ||
| 48 | + std::string outputPath = folderPath.substr(0, div + 1) + "result"; | ||
| 49 | + path p(outputPath); | ||
| 50 | + create_directory(p); | ||
| 51 | + | ||
| 52 | + //save output | ||
| 53 | + pcl::io::savePCDFile(outputPath + "/cloud_original.pcd", *cloud_original); | ||
| 54 | + pcl::io::savePCDFile(outputPath + "/cloud_filtered.pcd", *cloud_filtered); | ||
| 55 | + cv::imwrite(outputPath + "/img_original.png", raw); | ||
| 56 | + cv::imwrite(outputPath + "/img_filtered.png", filtered); | ||
| 57 | + | ||
| 58 | + return 0; | ||
| 59 | +} | ||
| ... | \ No newline at end of file | ... | \ No newline at end of file |
-
Please register or login to post a comment