File size: 6,462 Bytes
fe2b563 |
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 |
#include <iostream>
#include "ICP.h"
#include "io_pc.h"
#include "FRICP.h"
int main(int argc, char const ** argv)
{
typedef double Scalar;
typedef Eigen::Matrix<Scalar, 3, Eigen::Dynamic> Vertices;
typedef Eigen::Matrix<Scalar, 3, 1> VectorN;
std::string file_source;
std::string file_target;
std::string file_init = "./data/";
std::string res_trans_path;
std::string out_path;
bool use_init = false;
MatrixXX res_trans;
enum Method{ICP, AA_ICP, FICP, RICP, PPL, RPPL, SparseICP, SICPPPL} method=RICP;
if(argc == 5)
{
file_target = argv[1];
file_source = argv[2];
out_path = argv[3];
method = Method(std::stoi(argv[4]));
}
else if(argc==4)
{
file_target = argv[1];
file_source = argv[2];
out_path = argv[3];
}
else
{
std::cout << "Usage: target.ply source.ply out_path <Method>" << std::endl;
std::cout << "Method :\n"
<< "0: ICP\n1: AA-ICP\n2: Our Fast ICP\n3: Our Robust ICP\n4: ICP Point-to-plane\n"
<< "5: Our Robust ICP point to plane\n6: Sparse ICP\n7: Sparse ICP point to plane" << std::endl;
exit(0);
}
int dim = 3;
//--- Model that will be rigidly transformed
Vertices vertices_source, normal_source, src_vert_colors;
read_file(vertices_source, normal_source, src_vert_colors, file_source);
std::cout << "source: " << vertices_source.rows() << "x" << vertices_source.cols() << std::endl;
//--- Model that source will be aligned to
Vertices vertices_target, normal_target, tar_vert_colors;
read_file(vertices_target, normal_target, tar_vert_colors, file_target);
std::cout << "target: " << vertices_target.rows() << "x" << vertices_target.cols() << std::endl;
// scaling
Eigen::Vector3d source_scale, target_scale;
source_scale = vertices_source.rowwise().maxCoeff() - vertices_source.rowwise().minCoeff();
target_scale = vertices_target.rowwise().maxCoeff() - vertices_target.rowwise().minCoeff();
double scale = std::max(source_scale.norm(), target_scale.norm());
std::cout << "scale = " << scale << std::endl;
vertices_source /= scale;
vertices_target /= scale;
/// De-mean
VectorN source_mean, target_mean;
source_mean = vertices_source.rowwise().sum() / double(vertices_source.cols());
target_mean = vertices_target.rowwise().sum() / double(vertices_target.cols());
vertices_source.colwise() -= source_mean;
vertices_target.colwise() -= target_mean;
double time;
// set ICP parameters
ICP::Parameters pars;
// set Sparse-ICP parameters
SICP::Parameters spars;
spars.p = 0.4;
spars.print_icpn = false;
/// Initial transformation
if(use_init)
{
MatrixXX init_trans;
read_transMat(init_trans, file_init);
init_trans.block(0, dim, dim, 1) /= scale;
init_trans.block(0,3,3,1) += init_trans.block(0,0,3,3)*source_mean - target_mean;
pars.use_init = true;
pars.init_trans = init_trans;
spars.init_trans = init_trans;
}
///--- Execute registration
std::cout << "begin registration..." << std::endl;
FRICP<3> fricp;
double begin_reg = omp_get_wtime();
double converge_rmse = 0;
switch(method)
{
case ICP:
{
pars.f = ICP::NONE;
pars.use_AA = false;
fricp.point_to_point(vertices_source, vertices_target, source_mean, target_mean, pars);
res_trans = pars.res_trans;
break;
}
case AA_ICP:
{
AAICP::point_to_point_aaicp(vertices_source, vertices_target, source_mean, target_mean, pars);
res_trans = pars.res_trans;
break;
}
case FICP:
{
pars.f = ICP::NONE;
pars.use_AA = true;
fricp.point_to_point(vertices_source, vertices_target, source_mean, target_mean, pars);
res_trans = pars.res_trans;
break;
}
case RICP:
{
pars.f = ICP::WELSCH;
pars.use_AA = true;
fricp.point_to_point(vertices_source, vertices_target, source_mean, target_mean, pars);
res_trans = pars.res_trans;
break;
}
case PPL:
{
pars.f = ICP::NONE;
pars.use_AA = false;
if(normal_target.size()==0)
{
std::cout << "Warning! The target model without normals can't run Point-to-plane method!" << std::endl;
exit(0);
}
fricp.point_to_plane(vertices_source, vertices_target, normal_source, normal_target, source_mean, target_mean, pars);
res_trans = pars.res_trans;
break;
}
case RPPL:
{
pars.nu_end_k = 1.0/6;
pars.f = ICP::WELSCH;
pars.use_AA = true;
if(normal_target.size()==0)
{
std::cout << "Warning! The target model without normals can't run Point-to-plane method!" << std::endl;
exit(0);
}
fricp.point_to_plane_GN(vertices_source, vertices_target, normal_source, normal_target, source_mean, target_mean, pars);
res_trans = pars.res_trans;
break;
}
case SparseICP:
{
SICP::point_to_point(vertices_source, vertices_target, source_mean, target_mean, spars);
res_trans = spars.res_trans;
break;
}
case SICPPPL:
{
if(normal_target.size()==0)
{
std::cout << "Warning! The target model without normals can't run Point-to-plane method!" << std::endl;
exit(0);
}
SICP::point_to_plane(vertices_source, vertices_target, normal_target, source_mean, target_mean, spars);
res_trans = spars.res_trans;
break;
}
}
std::cout << "Registration done!" << std::endl;
double end_reg = omp_get_wtime();
time = end_reg - begin_reg;
vertices_source = scale * vertices_source;
out_path = out_path + "m" + std::to_string(method);
Eigen::Affine3d res_T;
res_T.linear() = res_trans.block(0,0,3,3);
res_T.translation() = res_trans.block(0,3,3,1);
res_trans_path = out_path + "trans.txt";
std::ofstream out_trans(res_trans_path);
res_trans.block(0,3,3,1) *= scale;
out_trans << res_trans << std::endl;
out_trans.close();
///--- Write result to file
std::string file_source_reg = out_path + "reg_pc.ply";
write_file(file_source, vertices_source, normal_source, src_vert_colors, file_source_reg);
return 0;
}
|