obj.cpp 2.79 KB
#include "common.h"
#include "cv_func.h"
#include "pcl_func.h"

/*
[input]
argc    = 3
argv[0] = program
argv[1] = vtk file
artv[2] = color img

[output]
obj file
mtl file
*/

int main(int argc, char** argv)
{
    if(argc != 3)
    {
        std::cout << "[Error] Program Usage: [./obj] [mesh.vtk] [color_img.png]" << std::endl;
        return -1;
    }

    //read vtk file
    pcl::PolygonMesh vtk_mesh;
    pcl::io::loadPolygonFileVTK(argv[1], vtk_mesh);

    //copy pointcloud from vtk file (vertices)
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
    pcl::fromPCLPointCloud2(vtk_mesh.cloud, *cloud);
    
    //mesh initialization
    pcl::TextureMesh mesh;
    mesh.cloud = vtk_mesh.cloud;
    std::vector<pcl::Vertices> vertices;

    //copy faces from vtk file
    vertices.resize(vtk_mesh.polygons.size());
    for(std::size_t i = 0; i < vtk_mesh.polygons.size(); i++)
    {
        vertices[i] = vtk_mesh.polygons[i];
    }
    mesh.tex_polygons.push_back(vertices);
    PCL_INFO("Input mesh contains %zu faces and %zu vertices\n",
            mesh.tex_polygons[0].size(),
            static_cast<std::size_t>(cloud->size()));
    PCL_INFO("...Done.\n");

    //intrinsic setup
    camInfo cam;
    realsenseSetUp(cam);
    
    //one material
    mesh.tex_materials.resize(1);
    
    pcl::TexMaterial mesh_material;
    mesh_material.tex_name = "texture image";
    std::string color_img = argv[2];
    color_img = color_img.substr(color_img.find_last_of("/\\") + 1);
    mesh_material.tex_file = color_img;

    mesh_material.tex_Ka.r = 0.2f;
    mesh_material.tex_Ka.g = 0.2f;
    mesh_material.tex_Ka.b = 0.2f;

    mesh_material.tex_Kd.r = 0.8f;
    mesh_material.tex_Kd.g = 0.8f;
    mesh_material.tex_Kd.b = 0.8f;

    mesh_material.tex_Ks.r = 1.0f;
    mesh_material.tex_Ks.g = 1.0f;
    mesh_material.tex_Ks.b = 1.0f;

    mesh_material.tex_d = 1.0f;
    mesh_material.tex_Ns = 75.0f;
    mesh_material.tex_illum = 2;

    mesh.tex_materials[0] = mesh_material;

    //normal estimation
    PCL_INFO ("\nEstimating normals...\n");
    pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> n;
    pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>);
    pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
    tree->setInputCloud(cloud);
    n.setInputCloud(cloud);
    n.setSearchMethod(tree);
    n.setKSearch(20);
    n.compute(*normals);

    pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals(new pcl::PointCloud<pcl::PointNormal>);
    pcl::concatenateFields(*cloud, *normals, *cloud_with_normals);
    pcl::toPCLPointCloud2(*cloud_with_normals, mesh.cloud);
    PCL_INFO("...Done.\n");

    //obj file creating
    PCL_INFO("\nSaving mesh to textured_mesh.obj\n");
    saveOBJFile("mesh.obj", mesh, 5, cloud, cam);

    return 0;
}