12 vector< Vector3d, Eigen::aligned_allocator<Vector3d> > camps;
13 vector< Matrix3d, Eigen::aligned_allocator<Matrix3d> > camRs;
14 vector< Vector3d, Eigen::aligned_allocator<Vector3d> > camts;
15 vector< Vector3d, Eigen::aligned_allocator<Vector3d> > ptps;
16 vector< Vector3i, Eigen::aligned_allocator<Vector3i> > ptcs;
17 vector< vector< Vector4d, Eigen::aligned_allocator<Vector4d> > > ptts;
23 int ncams = camps.size();
24 int npts = ptps.size();
26 for (
int i=0; i<npts; i++)
27 nprjs += (
int)ptts[i].size();
31 cout <<
"Setting up nodes..." << flush;
32 for (
int i=0; i<ncams; i++)
35 Vector3d &camp = camps[i];
36 CamParams cpars = {camp[0],camp[0],0,0,0};
46 m180x << 1, 0, 0, 0, -1, 0, 0, 0, -1;
47 Matrix3d camR = m180x * camRs[i];
48 Quaternion<double> frq(camR.transpose());
60 Vector3d &camt = camts[i];
62 frt.head<3>() = -camRs[i].transpose() * camt;
67 sbaout.
addNode(frt, frq, cpars);
72 cout <<
"Setting up points..." << flush;
73 for (
int i=0; i<npts; i++)
76 Vector3d &ptp = ptps[i];
90 cout <<
"Setting up projections..." << flush;
91 for (
int i=0; i<npts; i++)
94 vector<Vector4d, Eigen::aligned_allocator<Vector4d> > &ptt = ptts[i];
95 int nprjs = ptt.size();
96 for (
int j=0; j<nprjs; j++)
99 Vector4d &prj = ptt[j];
100 int cami = (int)prj[0];
101 Vector2d pt = prj.segment<2>(2);
104 cout <<
"*** Cam index exceeds bounds: " << cami << endl;
109 cout <<
"done" << endl;
116 ofstream outfile(filename, ios_base::trunc);
119 cout <<
"Can't open file " << filename << endl;
123 outfile.precision(10);
124 outfile.setf(ios_base::scientific);
128 outfile <<
"# Bundle file v0.3" << endl;
130 outfile << sbain.
nodes.size() <<
' ' << sbain.
tracks.size() << endl;
134 m180x << 1, 0, 0, 0, -1, 0, 0, 0, -1;
138 for (i = 0; i < sbain.
nodes.size(); i++)
141 outfile << sbain.
nodes[i].Kcam(0, 0) <<
' ' << 0.0 <<
' ' << 0.0 << endl;
143 Quaternion<double> quat(sbain.
nodes[i].qrot);
146 Matrix3d rotmat = m180x * quat.toRotationMatrix().transpose();
148 outfile << rotmat(0, 0) <<
' ' << rotmat(0, 1) <<
' ' << rotmat(0, 2) << endl;
149 outfile << rotmat(1, 0) <<
' ' << rotmat(1, 1) <<
' ' << rotmat(1, 2) << endl;
150 outfile << rotmat(2, 0) <<
' ' << rotmat(2, 1) <<
' ' << rotmat(2, 2) << endl;
152 Vector3d trans = sbain.
nodes[i].trans.head<3>();
153 trans = -rotmat*trans;
154 outfile << trans(0) <<
' ' << trans(1) <<
' ' << trans(2) << endl;
157 outfile.setf(ios_base::fixed);
160 for (i = 0; i < sbain.
tracks.size(); i++)
163 outfile << sbain.
tracks[i].point(0) <<
' ' << sbain.
tracks[i].point(1)
164 <<
' ' << sbain.
tracks[i].point(2) << endl;
166 outfile <<
"255 255 255" << endl;
175 outfile << prjs.size() <<
' ';
178 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
180 Proj &prj = itr->second;
184 double cx = node.
Kcam(0, 2);
185 double cy = node.
Kcam(1, 2);
187 outfile << prj.
ndi <<
' ' << i <<
' ' << prj.
kp(0)-cx <<
' '
188 << -(prj.
kp(1)-cy) <<
' ';
198 vector< Vector3d, Eigen::aligned_allocator<Vector3d> > &camp,
199 vector< Matrix3d, Eigen::aligned_allocator<Matrix3d> > &camR,
200 vector< Vector3d, Eigen::aligned_allocator<Vector3d> > &camt,
201 vector< Vector3d, Eigen::aligned_allocator<Vector3d> > &ptp,
202 vector< Vector3i, Eigen::aligned_allocator<Vector3i> > &ptc,
203 vector< vector< Vector4d, Eigen::aligned_allocator<Vector4d> > > &ptt
209 cout <<
"Can't open file " << fin << endl;
217 if (!getline(ifs,line) || line !=
"# Bundle file v0.3")
219 cout <<
"Bad header" << endl;
222 cout <<
"Found Bundler 3.0 file" << endl;
226 if (!(ifs >> ncams >> npts))
228 cout <<
"Bad header" << endl;
231 cout <<
"Number of cameras: " << ncams <<
" Number of points: " << npts << endl;
233 cout <<
"Reading in camera data..." << flush;
234 for (
int i=0; i<ncams; i++)
236 double v1,v2,v3,v4,v5,v6,v7,v8,v9;
237 if (!(ifs >> v1 >> v2 >> v3))
239 cout <<
"Bad camera params at number " << i << endl;
242 camp.push_back(Vector3d(v1,v2,v3));
244 if (!(ifs >> v1 >> v2 >> v3 >> v4 >> v5 >> v6 >> v7 >> v8 >> v9))
246 cout <<
"Bad camera rotation matrix at number " << i << endl;
250 m << v1,v2,v3,v4,v5,v6,v7,v8,v9;
253 if (!(ifs >> v1 >> v2 >> v3))
255 cout <<
"Bad camera translation at number " << i << endl;
258 camt.push_back(Vector3d(v1,v2,v3));
260 cout <<
"done" << endl;
264 cout <<
"Reading in pts data..." << flush;
265 for (
int i=0; i<npts; i++)
270 if (!(ifs >> v1 >> v2 >> v3))
272 cout <<
"Bad point position at number " << i << endl;
275 ptp.push_back(Vector3d(v1,v2,v3));
277 if (!(ifs >> i1 >> i2 >> i3))
279 cout <<
"Bad point color at number " << i << endl;
282 ptc.push_back(Vector3i(i1,i2,i3));
287 cout <<
"Bad track count at number " << i << endl;
292 vector<Vector4d, Eigen::aligned_allocator<Vector4d> > &prjs = ptt[i];
293 for (
int j=0; j<nprjs; j++)
295 if (!(ifs >> i1 >> i2 >> v1 >> v2))
297 cout <<
"Bad track parameter at number " << i << endl;
300 prjs.push_back(Vector4d(i1,i2,v1,v2));
304 cout <<
"done" << endl;
308 for (
int i=0; i<npts; i++)
309 nprjs += ptt[i].size();
310 cout <<
"Number of projections: " << (int)nprjs << endl;
311 cout <<
"Average projections per camera: " << nprjs/(double)ncams << endl;
312 cout <<
"Average track length: " << nprjs/(double)npts << endl;
325 sprintf(name,
"%s-cams.txt",fname);
326 FILE *fn = fopen(name,
"w");
329 cout <<
"[WriteFile] Can't open file " << name << endl;
334 int ncams =
sba.nodes.size();
335 for (
int i=0; i<ncams; i++)
340 Quaternion<double> frq(nd.
w2n.block<3,3>(0,0));
341 fprintf(fn,
"%f %f %f %f ", frq.w(), frq.x(), frq.y(), frq.z());
342 Vector3d tr = nd.
w2n.col(3);
343 fprintf(fn,
"%f %f %f\n", tr[0], tr[1], tr[2]);
347 sprintf(name,
"%s-pts.txt",fname);
348 fn = fopen(name,
"w");
351 cout <<
"[WriteFile] Can't open file " << name << endl;
355 fprintf(fn,
"# X Y Z nframes frame0 x0 y0 frame1 x1 y1 ...\n");
359 for(
size_t i=0; i<
sba.tracks.size(); i++)
365 fprintf(fn,
"%f %f %f ", pt.x(), pt.y(), pt.z());
366 fprintf(fn,
"%d ",(
int)prjs.size());
369 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
371 Proj &prj = itr->second;
373 int cami = itr->first;
375 fprintf(fn,
" %d %f %f ",cami,prj.
kp[0],prj.
kp[1]);
383 sprintf(name,
"%s-calib.txt",fname);
384 fn = fopen(name,
"w");
387 cout <<
"[WriteFile] Can't open file " << name << endl;
391 Matrix3d &K =
sba.nodes[0].Kcam;
392 fprintf(fn,
"%f %f %f\n", K(0,0), K(0,1), K(0,2));
393 fprintf(fn,
"%f %f %f\n", K(1,0), K(1,1), K(1,2));
394 fprintf(fn,
"%f %f %f\n", K(2,0), K(2,1), K(2,2));
406 cout <<
"Can't open file " << fname << endl;
411 Eigen::IOFormat pfmt(16);
412 ofs <<
sba.A.format(pfmt) << endl;
421 sprintf(name,
"%s-A.tri",fname);
427 cout <<
"Can't open file " << fname << endl;
432 Eigen::IOFormat pfmt(16);
434 int nrows =
sba.A.rows();
435 int ncols =
sba.A.cols();
437 cout <<
"[WriteSparseA] Size: " << nrows <<
"x" << ncols << endl;
441 for (
int i=0; i<nrows; i++)
442 for (
int j=i; j<ncols; j++)
444 double a =
sba.A(i,j);
448 ofs << nrows <<
" " << ncols <<
" " << nnz <<
" 1" << endl;
450 for (
int i=0; i<nrows; i++)
451 for (
int j=i; j<ncols; j++)
453 double a =
sba.A(i,j);
455 ofs << i <<
" " << j <<
" " << setprecision(16) << a << endl;
461 sprintf(name,
"%s-B.txt",fname);
467 cout <<
"Can't open file " << fname << endl;
472 Eigen::IOFormat pfmt(16);
474 int nrows =
sba.B.rows();
476 ofs << nrows <<
" " << 1 << endl;
478 for (
int i=0; i<nrows; i++)
481 ofs << setprecision(16) << a << endl;
491 vector< Vector5d, Eigen::aligned_allocator<Vector5d> > camps;
492 vector< Vector4d, Eigen::aligned_allocator<Vector4d> > camqs;
493 vector< Vector3d, Eigen::aligned_allocator<Vector3d> > camts;
494 vector< Vector3d, Eigen::aligned_allocator<Vector3d> > ptps;
495 vector< vector< Vector11d, Eigen::aligned_allocator<Vector11d> > > ptts;
497 int ret =
ParseGraphFile(filename, camps, camqs, camts, ptps, ptts);
501 int ncams = camps.size();
502 int npts = ptps.size();
504 for (
int i=0; i<npts; i++)
505 nprjs += (
int)ptts[i].size();
510 for (
int i=0; i<ncams; i++)
514 CamParams cpars = {camp[0],camp[1],camp[2],camp[3],camp[4]};
520 Quaternion<double> frq(camqs[i]);
532 Vector3d &camt = camts[i];
534 frt.head<3>() = camt;
539 sbaout.
addNode(frt, frq, cpars);
545 for (
int i=0; i<npts; i++)
548 Vector3d &ptp = ptps[i];
563 for (
int i=0; i<npts; i++)
566 vector<Vector11d, Eigen::aligned_allocator<Vector11d> > &ptt = ptts[i];
567 int nprjs = ptt.size();
568 for (
int j=0; j<nprjs; j++)
572 int cami = (int)prj[0];
574 cout <<
"*** Cam index exceeds bounds: " << cami << endl;
577 Vector3d pt = prj.segment<3>(2);
582 Vector2d pt = prj.segment<2>(2);
597 static void make_qrot(
double rr,
double rp,
double ry, Vector4d &v)
599 double sr = sin(rr/2.0);
600 double cr = cos(rr/2.0);
601 double sp = sin(rp/2.0);
602 double cp = cos(rp/2.0);
603 double sy = sin(ry/2.0);
604 double cy = cos(ry/2.0);
605 v[0] = sr*cp*cy - cr*sp*sy;
606 v[1] = cr*sp*cy + sr*cp*sy;
607 v[2] = cr*cp*sy - sr*sp*cy;
608 v[3] = cr*cp*cy + sr*sp*sy;
612 vector<
Vector5d, Eigen::aligned_allocator<Vector5d> > &camp,
613 vector< Vector4d, Eigen::aligned_allocator<Vector4d> > &camq,
614 vector< Vector3d, Eigen::aligned_allocator<Vector3d> > &camt,
615 vector< Vector3d, Eigen::aligned_allocator<Vector3d> > &ptp,
618 vector< vector<
Vector11d, Eigen::aligned_allocator<Vector11d> > > &ptts
625 cout <<
"Can't open file " << fin << endl;
631 map<int,int> nodemap;
632 map<int,int> pointmap;
639 while (getline(ifs,line))
642 stringstream ss(line);
645 size_t pos = type.find(
"#");
646 if (pos != string::npos)
649 if (type ==
"VERTEX_SE3" ||
650 type ==
"VERTEX_CAM")
653 double tx,ty,tz,qx,qy,qz,qw,fx,fy,cx,cy,bline;
654 if (!(ss >> n >> tx >> ty >> tz >> qx >> qy >> qz >> qw >> fx >> fy >>
657 cout <<
"[ReadSPA] Bad VERTEX_SE3 at line " << nline << endl;
660 nodemap.insert(pair<int,int>(n,nid));
662 camt.push_back(Vector3d(tx,ty,tz));
663 Vector4d v(qx,qy,qz,qw);
669 cp << fx,fy,cx,cy,bline;
673 else if (type ==
"VERTEX_XYZ")
677 if (!(ss >> n >> tx >> ty >> tz))
679 cout <<
"[ReadSPA] Bad VERTEX_XYZ at line " << nline << endl;
682 pointmap.insert(pair<int,int>(n,pid));
684 ptp.push_back(Vector3d(tx,ty,tz));
687 else if (type ==
"EDGE_PROJECT_XYZ" ||
688 type ==
"EDGE_PROJECT_P2MC" ||
689 type ==
"EDGE_PROJECT_P2SC")
693 double cv0, cv1, cv2, cv3, cv4, cv5;
694 cv3 = cv4 =cv5 = 0.0;
698 if (type ==
"EDGE_PROJECT_P2SC")
700 if (!(ss >> n1 >> n2 >> u >> v >> d >>
701 cv0 >> cv1 >> cv2 >> cv3 >> cv4 >> cv5))
703 cout <<
"[ReadSPA] Bad EDGE_PROJECT_XYZ at line " << nline << endl;
709 if (!(ss >> n1 >> n2 >> u >> v >> cv0 >> cv1 >> cv2))
711 cout <<
"[ReadSPA] Bad EDGE_PROJECT_XYZ at line " << nline << endl;
717 map<int,int>::iterator it;
718 it = pointmap.find(n1);
719 if (it == pointmap.end())
721 cout <<
"[ReadSPA] Missing point index " << n1 <<
" at line " << nline << endl;
725 if (pi >= (
int)ptp.size())
727 cout <<
"[ReadSPA] Point index " << pi <<
" too large at line " << nline << endl;
732 it = nodemap.find(n2);
733 if (it == nodemap.end())
735 cout <<
"[ReadSPA] Missing camera index " << n2 <<
" at line " << nline << endl;
739 if (ci >= (
int)camp.size())
741 cout <<
"[ReadSPA] Camera index " << ci <<
" too large at line " << nline << endl;
747 if (ptts.size() < (
size_t)pi+1)
749 vector< Vector11d, Eigen::aligned_allocator<Vector11d> > &trk = ptts[pi];
751 tv << ci,pi,u,v,
d,cv0,cv1,cv2,cv3,cv4,cv5;
757 cout <<
"[ReadSPA] Undefined type <" << type <<
"> at line " << nline << endl;
764 int ncams = camp.size();
765 int npts = ptp.size();
766 for (
int i=0; i<npts; i++)
767 nprjs += ptts[i].size();
768 cout <<
"Number of cameras: " << ncams << endl;
769 cout <<
"Number of points: " << npts << endl;
770 cout <<
"Number of projections: " << (int)nprjs << endl;
771 cout <<
"Average projections per camera: " << nprjs/(double)ncams << endl;
772 cout <<
"Average track length: " << nprjs/(double)npts << endl;
785 ofstream outfile(filename, ios_base::trunc);
788 cout <<
"Can't open file " << filename << endl;
792 outfile.precision(5);
794 outfile.setf(ios_base::fixed);
805 int ncams =
sba.nodes.size();
806 for (i = 0; i < (
unsigned int)ncams; i++)
808 outfile <<
"VERTEX_CAM" <<
" ";
810 Vector3d trans =
sba.nodes[i].trans.head<3>();
811 outfile << trans(0) <<
' ' << trans(1) <<
' ' << trans(2) <<
' ';
812 Vector4d rot =
sba.nodes[i].qrot.coeffs();
813 outfile << rot(0) <<
' ' << rot(1) <<
' ' << rot(2) <<
' ' << rot(3) <<
' ';
815 outfile <<
sba.nodes[i].Kcam(0,0) <<
' ' <<
sba.nodes[i].Kcam(1,1) <<
' ' <<
816 sba.nodes[i].Kcam(0,2) <<
' ' <<
sba.nodes[i].Kcam(1,2) <<
' ' <<
sba.nodes[i].baseline << endl;
824 for (i = 0; i <
sba.tracks.size(); i++)
826 outfile <<
"VERTEX_XYZ" <<
' ' << ncams+i <<
' ';
828 outfile <<
sba.tracks[i].point(0) <<
' ' <<
sba.tracks[i].point(1)
829 <<
' ' <<
sba.tracks[i].point(2) << endl;
835 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
838 Proj &prj = itr->second;
841 outfile <<
"EDGE_PROJECT_P2SC ";
842 outfile << ncams+i <<
' ' << prj.
ndi <<
' ' << prj.
kp(0) <<
' '
843 << prj.
kp(1) <<
' ' << prj.
kp(2) <<
' ';
844 outfile <<
"1 0 0 0 1 1" << endl;
848 outfile <<
"EDGE_PROJECT_P2MC ";
849 outfile << ncams+i <<
' ' << prj.
ndi <<
' ' << prj.
kp(0) <<
' '
851 outfile <<
"1 0 1" << endl;
871 std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > ntrans,
872 std::vector< Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > nqrot,
873 std::vector< Eigen::Vector2i, Eigen::aligned_allocator<Eigen::Vector2i> > cind,
874 std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > ctrans,
875 std::vector< Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > cqrot,
876 std::vector< Eigen::Matrix<double,6,6>, Eigen::aligned_allocator<Eigen::Matrix<double,6,6> > > prec)
881 Quaternion<double> frq;
882 frq.coeffs() = nqrot[n];
885 if (frq.w() <= 0.0) frq.coeffs() = -frq.coeffs();
886 nd.
qrot = frq.coeffs();
891 v.head(3) = ntrans[n];
902 spa.
nodes.push_back(nd);
906 for (
int i=0; i<(int)ctrans.size(); i++)
909 con.
ndr = cind[i].x();
910 con.
nd1 = cind[i].y();
912 if ((con.
ndr == n && con.
nd1 <= n-1) ||
913 (con.
nd1 == n && con.
ndr <= n-1))
915 con.
tmean = ctrans[i];
916 Quaternion<double> qr;
917 qr.coeffs() = cqrot[i];
919 con.
qpmean = qr.inverse();
924 spa.
p2cons.push_back(con);
932 std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > ntrans;
933 std::vector< Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > nqrot;
934 std::vector< Eigen::Vector2i, Eigen::aligned_allocator<Eigen::Vector2i> > cind;
935 std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > ctrans;
936 std::vector< Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > cqrot;
937 std::vector< Eigen::Matrix<double,6,6>, Eigen::aligned_allocator<Eigen::Matrix<double,6,6> > > prec;
943 cout <<
"# [ReadSPAFile] Found " << (int)ntrans.size() <<
" nodes and "
944 << (int)cind.size() <<
" constraints" << endl;
946 int nnodes = ntrans.size();
949 for (
int i=0; i<nnodes; i++)
950 addnode(spaout, i, ntrans, nqrot, cind, ctrans, cqrot, prec);
990 Matrix<double,6,6> mt = m.transpose();
991 mt.diagonal().setZero();
997 std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > &ntrans,
998 std::vector< Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > &nqrot,
999 std::vector< Eigen::Vector2i, Eigen::aligned_allocator<Eigen::Vector2i> > &cind,
1000 std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > &ctrans,
1001 std::vector< Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > &cqrot,
1002 std::vector< Eigen::Matrix<double,6,6>, Eigen::aligned_allocator<Eigen::Matrix<double,6,6> > > &prec)
1007 cout <<
"Can't open file " << fin << endl;
1016 while (getline(ifs,line))
1019 stringstream ss(line);
1022 size_t pos = type.find(
"#");
1023 if (pos != string::npos)
1026 if (type ==
"VERTEX_SE3")
1029 double tx,ty,tz,rr,rp,ry;
1030 if (!(ss >> n >> tx >> ty >> tz >> rr >> rp >> ry))
1032 cout <<
"[ReadSPA] Bad VERTEX_SE3 at line " << nline << endl;
1035 ntrans.push_back(Vector3d(tx,ty,tz));
1041 if (type ==
"EDGE_SE3_SE3")
1044 double tx,ty,tz,rr,rp,ry;
1048 if (!(ss >> n1 >> n2 >> tx >> ty >> tz >> rr >> rp >> ry))
1050 cout <<
"[ReadSPA] Bad EDGE_SE3_SE3 at line " << nline << endl;
1053 cind.push_back(Vector2i(n1,n2));
1054 ctrans.push_back(Vector3d(tx,ty,tz));
1060 if (!(ss >> cv[0] >> cv[1] >> cv[2] >> cv[3] >> cv[4]
1061 >> cv[5] >> cv[6] >> cv[7] >> cv[8] >> cv[9]
1062 >> cv[10] >> cv[11] >> cv[12] >> cv[13] >> cv[14]
1063 >> cv[15] >> cv[16] >> cv[17] >> cv[18] >> cv[19] >> cv[20]))
1065 cout <<
"[ReadSPA] Bad EDGE_SE3_SE3 at line " << nline << endl;
1068 Matrix<double,6,6> m;