41 using namespace Eigen;
51 gettimeofday(&tv,NULL);
52 long long ts = tv.tv_sec;
64 #define F77_FUNC(func) func ## _ 66 extern int F77_FUNC(
dpotf2)(
char *uplo,
int *n,
double *a,
int *lda,
int *info);
67 extern int F77_FUNC(
dpotrf)(
char *uplo,
int *n,
double *a,
int *lda,
int *info);
68 extern int F77_FUNC(
dpotrs)(
char *uplo,
int *n,
int *nrhs,
double *a,
int *lda,
double *b,
int *ldb,
int *info);
69 extern int F77_FUNC(
dpotri)(
char *uplo,
int *n,
double *a,
int *lda,
int *info);
83 int SysSBA::addNode(Eigen::Matrix<double,4,1> &trans,
84 Eigen::Quaternion<double> &qrot,
99 return nodes.size()-1;
106 tracks.push_back(
Track(p));
107 return tracks.size()-1;
115 bool SysSBA::addProj(
int ci,
int pi, Eigen::Vector3d &q,
bool stereo)
120 if (tracks[pi].projections.count(ci) > 0)
122 if (tracks[pi].projections[ci].kp == q)
126 tracks[pi].projections[ci] =
Proj(ci, q, stereo);
129 Eigen::Matrix3d covar;
135 tracks[pi].projections[ci].setCovariance(covar);
145 bool SysSBA::addMonoProj(
int ci,
int pi, Eigen::Vector2d &q)
147 if (tracks[pi].projections.count(ci) > 0)
149 if (tracks[pi].projections[ci].kp.head(2) == q)
153 tracks[pi].projections[ci] =
Proj(ci, q);
160 bool SysSBA::addStereoProj(
int ci,
int pi, Eigen::Vector3d &q)
162 if (tracks[pi].projections.count(ci) > 0)
164 if (tracks[pi].projections[ci].kp == q)
168 tracks[pi].projections[ci] =
Proj(ci, q,
true);
171 Eigen::Matrix3d covar;
177 tracks[pi].projections[ci].setCovariance(covar);
184 void SysSBA::setProjCovariance(
int ci,
int pi, Eigen::Matrix3d &covar)
187 tracks[pi].projections[ci].setCovariance(covar);
191 void SysSBA::addPointPlaneMatch(
int ci0,
int pi0, Eigen::Vector3d normal0,
int ci1,
int pi1, Eigen::Vector3d normal1)
193 Point pt0 = tracks[pi0].point;
194 Point pt1 = tracks[pi1].point;
199 Vector3d proj_forward;
200 proj_forward = tracks[pi1].projections[ci1].kp;
202 addStereoProj(ci1, pi0, proj_forward);
204 Proj &forward_proj = tracks[pi0].projections[ci1];
216 proj_fake = tracks[pi0].projections[ci0].kp;
217 addStereoProj(ci0, pi1, proj_fake);
218 Proj &fake_proj = tracks[pi1].projections[ci0];
224 Vector3d proj_backward;
226 proj_backward = tracks[pi0].projections[ci0].kp;
227 addStereoProj(ci0, pi1, proj_backward);
229 Proj &backward_proj = tracks[pi1].projections[ci0];
239 void SysSBA::updateNormals()
241 for(
size_t i=0; i<tracks.size(); i++)
243 ProjMap &prjs = tracks[i].projections;
244 if (prjs.size() == 0)
continue;
246 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
248 Proj &prj = itr->second;
254 Quaterniond qrot = nodes[prj.
ndi].qrot;
264 Point &pt0 = tracks[i].point;
267 Vector3d w = pt0.head<3>()-plane_point;
268 Vector3d projpt = pt0.head<3>() - (w.dot(plane_normal))*plane_normal;
275 int SysSBA::countProjs()
278 for(
size_t i=0; i<tracks.size(); i++)
280 ProjMap &prjs = tracks[i].projections;
289 double SysSBA::calcCost()
292 for(
size_t i=0; i<tracks.size(); i++)
294 ProjMap &prjs = tracks[i].projections;
295 if (prjs.size() == 0)
continue;
296 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
298 Proj &prj = itr->second;
300 double err = prj.
calcErr(nodes[prj.
ndi],tracks[i].point,huber);
310 double SysSBA::calcCost(
double dist)
315 for(
size_t i=0; i<tracks.size(); i++)
317 ProjMap &prjs = tracks[i].projections;
318 if (prjs.size() == 0)
continue;
319 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
321 Proj &prj = itr->second;
323 double err = prj.
calcErr(nodes[prj.
ndi],tracks[i].point);
336 double SysSBA::calcRMSCost(
double dist)
342 for(
size_t i=0; i<tracks.size(); i++)
344 ProjMap &prjs = tracks[i].projections;
345 if (prjs.size() == 0)
continue;
346 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
348 Proj &prj = itr->second;
350 double err = prj.
calcErr(nodes[prj.
ndi],tracks[i].point,huber);
359 return sqrt(cost/(
double)nprjs);
365 double SysSBA::calcAvgError()
370 for(
size_t i=0; i<tracks.size(); i++)
372 ProjMap &prjs = tracks[i].projections;
373 if (prjs.size() == 0)
continue;
374 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
376 Proj &prj = itr->second;
378 prj.
calcErr(nodes[prj.
ndi],tracks[i].point,huber);
384 return cost/(double)nprjs;
389 int SysSBA::numBadPoints()
393 for(
size_t i=0; i<tracks.size(); i++)
395 ProjMap &prjs = tracks[i].projections;
396 if (prjs.size() == 0)
continue;
397 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
399 Proj &prj = itr->second;
402 if (prj.
err[0] == 0.0 && prj.
err[1] == 0.0 && prj.
err[2] == 0.0)
417 int SysSBA::countBad(
double dist)
422 double b2 = HUBER*HUBER;
423 dist = 2*b2*(sqrt(1+dist/b2)-1);
426 for (
int i=0; i<(int)tracks.size(); i++)
428 ProjMap &prjs = tracks[i].projections;
429 if (prjs.size() == 0)
continue;
430 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
432 Proj &prj = itr->second;
446 int SysSBA::removeBad(
double dist)
451 for (
int i=0; i<(int)tracks.size(); i++)
453 ProjMap &prjs = tracks[i].projections;
454 if (prjs.size() == 0)
continue;
455 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
457 Proj &prj = itr->second;
472 int SysSBA::reduceTracks()
475 for (
int i=0; i<(int)tracks.size(); i++)
477 ProjMap &prjs = tracks[i].projections;
481 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); )
483 Proj &prj = itr->second;
505 void SysSBA::printStats()
507 int ncams = nodes.size();
508 vector<map<int,int>, Eigen::aligned_allocator<map<int,int> > > conns;
510 VectorXi dcnt(ncams);
517 int npts = tracks.size();
522 if (tracks.size() > 0)
524 for (
int i=0; i<npts; i++)
526 int s = (int)tracks[i].projections.size();
531 cout <<
"[SBAsys] Cameras: " << ncams <<
" Points: " << npts
532 <<
" Projections: " << nprjs <<
" Hessian elements: " << nhs << endl;
533 cout <<
"[SBAsys] Average " << (double)nprjs/(
double)npts
534 <<
" projections per track and " << (double)nprjs/(
double)ncams
535 <<
" projections per camera" << endl;
537 cout <<
"[SBAsys] Checking camera order in projections..." << flush;
538 for (
int i=0; i<npts; i++)
541 ProjMap &prjs = tracks[i].projections;
545 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
548 Proj &prj = itr->second;
563 if (j < (
int)prjs.size()-1)
565 map<int,int> &pm = conns[cami];
566 map<int,int>::iterator it;
567 for(ProjMap::iterator itr2 = itr; itr2 != prjs.end(); itr2++)
569 Proj &prj2 = itr2->second;
570 int cami2 = prj2.
ndi;
571 map<int,int> &pm2 = conns[cami2];
581 pm2.find(cami)->second++;
597 cout <<
"ok" << endl;
600 cout <<
"[SBAsys] Number of invalid projections: " << nbad << endl;
601 cout <<
"[SBAsys] Number of null tracks: " << n0 <<
" Number of single tracks: " << n1 <<
" Number of double tracks: " << n2 << endl;
606 for (
int i=0; i<ncams; i++)
608 if (dcnt(i) == 0) dnz++;
609 if (dcnt(i) < 5) dn5++;
611 cout <<
"[SBAsys] Number of disconnected cameras: " << dnz << endl;
612 cout <<
"[SBAsys] Number of cameras with <5 projs: " << dn5 << endl;
627 for (
int i=0; i<ncams; i++)
629 int nc = conns[i].size();
633 map<int,int>::iterator it;
634 for (it = conns[i].begin(); it != conns[i].end(); it++)
636 int np = (*it).second;
638 if (np < nmin) nmin = np;
639 if (np > nmax) nmax = np;
647 cout <<
"[SBAsys] Number of camera connections: " << nconns/2 <<
" which is " 648 << (double)nconns/(
double)ncams <<
" connections per camera and " 649 << (nconns+ncams)*100.0/(ncams*ncams) <<
" percent matrix fill" << endl;
650 cout <<
"[SBAsys] Min connection points: " << nmin <<
" Max connection points: " 651 << nmax <<
" Average connection points: " << (double)ntot/(
double)nconns << endl;
652 cout <<
"[SBAsys] Total connection projections: " << ntot << endl;
653 cout <<
"[SBAsys] Connections with less than 5 points: " << nc5/2 <<
" 10 pts: " << nc10/2
654 <<
" 20 pts: " << nc20/2 <<
" 50 pts: " << nc50/2 << endl;
659 vector<map<int,int> > SysSBA::generateConns_()
661 int ncams = nodes.size();
662 vector<map<int,int> > conns;
666 connMat.resize(ncams);
667 for (
int i=0; i<ncams; i++)
669 vector<bool> &bm = connMat[i];
670 bm.assign(ncams,
false);
674 for (
int i=0; i<(int)tracks.size(); i++)
677 ProjMap &prjs = tracks[i].projections;
678 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
680 Proj &prj = itr->second;
689 if (j < (
int)prjs.size()-1)
691 map<int,int> &pm = conns[cami];
692 map<int,int>::iterator it;
693 for(ProjMap::iterator itr2 = itr; itr2 != prjs.end(); itr2++)
695 Proj &prj2 = itr2->second;
696 int cami2 = prj2.
ndi;
697 map<int,int> &pm2 = conns[cami2];
707 pm2.find(cami)->second++;
720 void SysSBA::setConnMat(
int minpts)
723 int ncams = nodes.size();
725 vector<map<int,int> > conns = generateConns_();
728 multimap<int,pair<int,int> > weakcs;
729 for (
int i=0; i<ncams; i++)
731 map<int,int> cs = conns[i];
732 map<int,int>::iterator it;
733 for (it = cs.begin(); it != cs.end(); it++)
735 if (it->second < minpts && it->first > i)
736 weakcs.insert(pair<
int,pair<int,int> >(it->second, pair<int,int>(i,it->first)));
740 cout <<
"[SetConnMat] Found " << weakcs.size() <<
" connections with < " 741 << minpts <<
" points" << endl;
745 multimap<int,pair<int,int> >::iterator it;
746 for (it = weakcs.begin(); it != weakcs.end(); it++)
748 int c0 = it->second.first;
749 int c1 = it->second.second;
750 if (conns[c0].size() > 1 && conns[c1].size() > 1)
753 conns[c0].erase(conns[c0].find(c1));
754 conns[c1].erase(conns[c1].find(c0));
756 connMat[c0][c1] =
true;
757 connMat[c1][c0] =
true;
761 cout <<
"[SetConnMat] Erased " << n <<
" connections" << endl;
768 void SysSBA::setConnMatReduced(
int maxconns)
771 int ncams = nodes.size();
773 vector<map<int,int> > conns = generateConns_();
776 multimap<int,pair<int,int> > weakcs;
777 for (
int i=0; i<ncams; i++)
779 map<int,int> cs = conns[i];
780 map<int,int>::iterator it;
781 for (it = cs.begin(); it != cs.end(); it++)
784 weakcs.insert(pair<
int,pair<int,int> >(-it->second, pair<int,int>(i,it->first)));
791 found.assign(ncams,0);
792 multimap<int,pair<int,int> >::iterator it;
793 for (it = weakcs.begin(); it != weakcs.end(); it++)
795 int c0 = it->second.first;
796 int c1 = it->second.second;
797 if (found[c0] < maxconns || found[c1] < maxconns)
803 connMat[c0][c1] =
false;
804 connMat[c1][c0] =
false;
808 cout <<
"[SetConnMat] Found " << n <<
" connections in spanning tree" << endl;
815 SysSBA::tsplit(
int tri,
int len)
817 ProjMap prjs = tracks[tri].projections;
818 tracks[tri].projections.clear();
822 if ((
int)prjs.size() == len+1) len = len+1;
826 while (prjs.size() > 0 && i < len)
829 ProjMap::iterator randomitr = prjs.begin();
830 std::advance( randomitr, rand() % prjs.size());
831 Proj &prj = randomitr->second;
834 addProj(prj.ndi, tri, prj.kp, prj.stereo);
835 prjs.erase(randomitr);
840 int pti = tracks.size();
841 while (prjs.size() > 0)
844 if ((
int)prjs.size() == len+1) len = len+1;
845 while (prjs.size() > 0 && i < len)
848 ProjMap::iterator randomitr = prjs.begin();
849 std::advance( randomitr, rand() % prjs.size());
850 Proj &prj = randomitr->second;
854 addProj(prj.ndi, pti, prj.kp, prj.stereo);
855 prjs.erase(randomitr);
858 tracks[pti].point = tracks[tri].point;
867 int SysSBA::reduceLongTracks(
double len)
871 int npts = tracks.size();
873 #if 1 // this algorithm splits tracks 878 for (
int i=0; i<npts; i++)
880 if ((
int)tracks[i].projections.size() > ilen)
884 int ts = tracks[i].projections.size()+1;
892 #else // this throws them out 896 multimap<int,int> ordps;
899 for (
int i=0; i<npts; i++)
900 if ((
int)tracks[i].size() > ilen)
901 ordps.insert(pair<int,int>(-(
int)tracks[i].size(), i));
905 int nn = ordps.size();
906 map<int,int>::iterator it = ordps.begin();
908 for (
int i=0; i<nn; i++, it++)
909 rem.push_back(it->second);
910 sort(rem.begin(),rem.end());
911 cout <<
"Finished finding " << rem.size() <<
" tracks" << endl;
913 std::vector<Point, Eigen::aligned_allocator<Point> > pts;
914 std::vector< std::vector<MonoProj, Eigen::aligned_allocator<MonoProj> >,
915 Eigen::aligned_allocator<std::vector<MonoProj, Eigen::aligned_allocator<MonoProj> > > > trs;
920 for (
int i=0; i<npts; i++)
922 if (rem.size()>n && i == rem[n])
927 pts.push_back(points[i]);
928 vector<MonoProj, Eigen::aligned_allocator<MonoProj> > &prjs = tracks[i];
931 trs.push_back(tracks[i]);
936 points.resize(pts.size());
937 tracks.resize(pts.size());
950 int SysSBA::remExcessTracks(
int minpts)
954 int npts = tracks.size();
956 vector<map<int,int> > conns = generateConns_();
959 multimap<int,int> ordtrs;
960 for (
int i=0; i<npts; i++)
961 ordtrs.insert(pair<int,int>((
int)tracks[i].projections.size(),i));
965 multimap<int,int>::reverse_iterator it;
966 for (it = ordtrs.rbegin(); it != ordtrs.rend(); it++)
968 int tri = it->second;
969 ProjMap &prjs = tracks[tri].projections;
971 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
973 Proj &prj = itr->second;
976 for(ProjMap::iterator itr2 = itr; itr2 != prjs.end(); itr2++)
978 Proj &prj2 = itr2->second;
980 if (conns[c0].find(c1)->second <= minpts)
991 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
993 Proj &prj = itr->second;
995 for(ProjMap::iterator itr2 = itr; itr2 != prjs.end(); itr2++)
997 Proj &prj2 = itr2->second;
999 conns[c0].find(c1)->second--;
1000 conns[c1].find(c0)->second--;
1003 remtrs.push_back(tri);
1008 for (
int i=0; i<(int)remtrs.size(); i++)
1010 int s = tracks[remtrs[i]].projections.size();
1014 cout <<
"[RemExcessTracks] Can erase " << remtrs.size() <<
" tracks with " << hms <<
" H entries" << endl;
1016 std::sort(remtrs.begin(),remtrs.end());
1018 std::vector<Track, Eigen::aligned_allocator<Track> > trs;
1023 for (
int i=0; i<npts; i++)
1025 if ((
int)remtrs.size()>n && i == remtrs[n])
1033 trs.push_back(tracks[i]);
1037 cout <<
"[RemExcessTracks] Erased " << n <<
" tracks" << endl;
1040 tracks.resize(trs.size());
1043 return remtrs.size();
1051 void SysSBA::setupSys(
double sLambda)
1054 int nFree = nodes.size() - nFixed;
1055 A.setZero(6*nFree,6*nFree);
1057 VectorXi dcnt(nFree);
1058 dcnt.setZero(nFree);
1061 double lam = 1.0 + sLambda;
1064 for(
size_t pi=0; pi<tracks.size(); pi++)
1066 ProjMap &prjs = tracks[pi].projections;
1067 if (prjs.size() < 1)
continue;
1070 if (prjs.size() > jps.size())
1071 jps.resize(prjs.size());
1082 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++, ii++)
1084 Proj &prj = itr->second;
1086 int ci = (prj.
ndi - nFixed) * 6;
1092 if (!nodes[prj.
ndi].isFixed)
1094 dcnt(prj.
ndi - nFixed)++;
1096 A.block<6,6>(ci,ci) += prj.
jp->
Hcc;
1097 B.block<6,1>(ci,0) -= prj.
jp->
JcTE;
1104 Hpp.diagonal() *= lam;
1105 Matrix3d Hppi = Hpp.inverse();
1106 Vector3d &tp = tps[pi];
1110 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
1112 Proj &prj = itr->second;
1114 if (nodes[prj.
ndi].isFixed)
continue;
1115 int ci = (prj.
ndi - nFixed) * 6;
1117 B.block<6,1>(ci,0) -= prj.
jp->
Hpc.transpose() * tp;
1118 prj.
Tpc = prj.
jp->
Hpc.transpose() * Hppi;
1121 for(ProjMap::iterator itr2 = itr; itr2 != prjs.end(); itr2++)
1123 Proj &prj2 = itr2->second;
1125 if (nodes[prj2.
ndi].isFixed)
continue;
1126 int ci2 = (prj2.
ndi - nFixed) * 6;
1129 A.block<6,6>(ci,ci2) -= prj.
Tpc * prj2.
jp->
Hpc;
1132 A.block<6,6>(ci2,ci) = A.block<6,6>(ci,ci2).transpose();
1139 A.diagonal() *= lam;
1142 for (
int i=0; i<6*nFree; i++)
1143 for (
int j=0; j<6*nFree; j++)
1144 if (std::isnan(A(i,j)) ) { printf(
"[SetupSys] NaN in A\n"); *(
int *)0x0 = 0; }
1146 for (
int j=0; j<6*nFree; j++)
1147 if (std::isnan(B[j]) ) { printf(
"[SetupSys] NaN in B\n"); *(
int *)0x0 = 0; }
1150 for (
int i=0; i<nFree; i++)
1151 if (dcnt(i) == 0) ndc++;
1154 cout <<
"[SetupSys] " << ndc <<
" disconnected nodes" << endl;
1165 void SysSBA::setupSparseSys(
double sLambda,
int iter,
int sparseType)
1168 int nFree = nodes.size() - nFixed;
1169 if (nFree < 0) nFree = 0;
1171 long long t0, t1, t2, t3;
1174 csp.setupBlockStructure(nFree);
1176 csp.setupBlockStructure(0);
1180 VectorXi dcnt(nFree);
1181 dcnt.setZero(nFree);
1184 double lam = 1.0 + sLambda;
1187 bool useConnMat = connMat.size() > 0;
1191 for(
size_t pi=0; pi<tracks.size(); pi++)
1193 ProjMap &prjs = tracks[pi].projections;
1194 if (prjs.size() < 1)
continue;
1197 if (prjs.size() > jps.size())
1198 jps.resize(prjs.size());
1209 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++, ii++)
1211 Proj &prj = itr->second;
1213 int ni = prj.
ndi - nFixed;
1220 if (!nodes[prj.
ndi].isFixed)
1222 dcnt(prj.
ndi - nFixed)++;
1225 csp.addDiagBlock(prj.
jp->
Hcc,ni);
1226 csp.B.block<6,1>(ci,0) -= prj.
jp->
JcTE;
1233 Hpp.diagonal() *= lam;
1234 Matrix3d Hppi = Hpp.inverse();
1235 Vector3d &tp = tps[pi];
1239 for(ProjMap::iterator itr = prjs.begin(); itr != prjs.end(); itr++)
1241 Proj &prj = itr->second;
1243 if (nodes[prj.
ndi].isFixed)
continue;
1244 int ni = prj.
ndi - nFixed;
1247 csp.B.block<6,1>(ci,0) -= prj.
jp->
Hpc.transpose() * tp;
1248 prj.
Tpc = prj.
jp->
Hpc.transpose() * Hppi;
1252 for(ProjMap::iterator itr2 = itr; itr2 != prjs.end(); itr2++)
1254 Proj &prj2 = itr2->second;
1256 if (nodes[prj2.
ndi].isFixed)
continue;
1257 int ni2 = prj2.
ndi - nFixed;
1258 if (useConnMat && connMat[prj.
ndi][prj2.
ndi])
1263 Matrix<double,6,6> m = -prj.
Tpc * prj2.
jp->
Hpc;
1265 csp.addDiagBlock(m,ni);
1267 csp.addOffdiagBlock(m,ni,ni2);
1271 Matrix<double,6,6> m = -prj.
Tpc * prj.
jp->
Hpc;
1272 csp.addDiagBlock(m,ni);
1285 csp.incDiagBlocks(lam);
1287 csp.setupCSstructure(lam,iter==0);
1292 printf(
"\n[SetupSparseSys] Block: %0.1f Cons: %0.1f CS: %0.1f\n",
1293 (t1-t0)*.001, (t2-t1)*.001, (t3-t2)*.001);
1296 for (
int i=0; i<nFree; i++)
1297 if (dcnt(i) == 0) ndc++;
1300 cout <<
"[SetupSys] " << ndc <<
" disconnected nodes" << endl;
1312 int SysSBA::doSBA(
int niter,
double sLambda,
int useCSparse,
double initTol,
int maxCGiter)
1316 oldpoints.resize(tracks.size());
1320 int npts = tracks.size();
1321 int ncams = nodes.size();
1326 for(
size_t i=0; i<tracks.size(); i++)
1328 oldpoints[i] = tracks[i].point;
1329 nprjs += tracks[i].projections.size();
1332 if (nprjs == 0 || npts == 0 || ncams == 0)
1344 cout <<
"[doSBA] No fixed frames" << endl;
1347 for (
int i=0; i<ncams; i++)
1349 Node &nd = nodes[i];
1356 nd.
setDr(useLocalAngles);
1360 double laminc = 2.0;
1361 double lamdec = 0.5;
1363 sqMinDelta = 1e-8 * 1e-8;
1365 double cost = calcCost();
1369 cout << iter <<
" Initial squared cost: " << cost <<
" which is " 1370 << sqrt(cost/nprjs) <<
" rms pixel error and " 1371 << calcAvgError() <<
" average reproj error; " 1372 << numBadPoints() <<
" bad points" << endl;
1375 for (; iter<niter; iter++)
1386 setupSparseSys(lambda,iter,useCSparse);
1397 sprintf(fn,
"A%d.txt",xs);
1398 printf(
"Writing file %s\n",fn);
1399 FILE *fd = fopen(fn,
"w");
1400 fprintf(fd,
"%d %d\n",xs,xs);
1401 for (
int ii=0; ii<xs; ii++)
1402 for (
int jj=0; jj<xs; jj++)
1403 fprintf(fd,
"%.16g\n",A(ii,jj));
1406 sprintf(fn,
"B%d.txt",xs);
1408 fprintf(fd,
"%d\n",xs);
1409 for (
int ii=0; ii<xs; ii++)
1410 fprintf(fd,
"%.16g\n",B(ii));
1419 if (csp.B.rows() != 0)
1421 int iters = csp.doBPCG(maxCGiter,initTol,iter);
1422 cout <<
"[Block PCG] " << iters <<
" iterations" << endl;
1425 else if (useCSparse > 0)
1427 if (csp.B.rows() != 0)
1429 bool ok = csp.doChol();
1431 cout <<
"[DoSBA] Sparse Cholesky failed!" << endl;
1437 A.llt().solveInPlace(B);
1439 printf(
"\nDoing dpotrf/dpotrs\n");
1440 double *a = A.data();
1441 int info, m = B.size();
1442 double *x = B.data();
1445 F77_FUNC(
dpotrs)(
"U", (
int *)&m, (
int *)&nrhs, a, (
int *)&m, x, (
int *)&m, &info);
1454 VectorXd &BB = useCSparse ? csp.B : B;
1458 double sqDiff = BB.squaredNorm();
1459 if (sqDiff < sqMinDelta)
1462 cout <<
"Converged with delta: " << sqrt(sqDiff) << endl;
1468 for(vector<
Node, Eigen::aligned_allocator<Node> >::iterator itr = nodes.begin(); itr != nodes.end(); itr++)
1474 nd.
trans.head<3>() += BB.segment<3>(ci);
1478 Quaternion<double> qr;
1479 qr.vec() = BB.segment<3>(ci+3);
1483 qr.w() = sqrt(1.0 - qr.vec().squaredNorm());
1490 nd.
qrot.coeffs().head<3>() += BB.segment<3>(ci+3);
1496 nd.
setDr(useLocalAngles);
1503 for(vector<
Track, Eigen::aligned_allocator<Track> >::iterator itr = tracks.begin();
1504 itr != tracks.end(); itr++, pi++)
1506 ProjMap &prjs = itr->projections;
1507 if (prjs.size() < 1)
continue;
1508 Vector3d tp = tps[pi];
1510 for(ProjMap::iterator pitr = prjs.begin(); pitr != prjs.end(); pitr++)
1512 Proj &prj = pitr->second;
1514 if (nodes[prj.
ndi].isFixed)
continue;
1515 int ci = (prj.
ndi - nFixed) * 6;
1517 tp -= prj.
Tpc.transpose() * BB.segment<6>(ci);
1520 oldpoints[pi] = tracks[pi].point;
1521 tracks[pi].point.head(3) += tp;
1528 double newcost = calcCost();
1533 cout << iter <<
" Updated squared cost: " << newcost <<
" which is " 1534 << sqrt(newcost/(
double)nprjs) <<
" rms pixel error and " 1535 << calcAvgError() <<
" average reproj error; " 1536 << numBadPoints() <<
" bad points" << endl;
1551 for(
int i=0; i < (int)tracks.size(); i++)
1553 tracks[i].point = oldpoints[i];
1556 for(
int i=0; i < (int)nodes.size(); i++)
1558 Node &nd = nodes[i];
1564 nd.
setDr(useLocalAngles);
1570 cout << iter <<
" Downdated cost: " << cost << endl;
1575 if (iter == 0 && verbose > 0)
1576 printf(
"\n[SBA] Cost: %0.2f ms Setup: %0.2f ms Solve: %0.2f ms Update: %0.2f ms Total: %0.2f ms\n\n",
1577 0.001*(
double)(t4-t3),
1578 0.001*(
double)(t1-t0),
1579 0.001*(
double)(t2-t1),
1580 0.001*(
double)(t3-t2),
1581 0.001*(
double)(t4-t0));
1592 void SysSBA::mergeTracks(std::vector<std::pair<int,int> > &prs)
1595 int ntrs = tracks.size();
1599 for (
int i=0; i<ntrs; i++)
1603 for (
int i=0; i<(int)prs.size(); i++)
1605 pair<int,int> &pr = prs[i];
1606 int p0 = min(pr.first,pr.second);
1607 int p1 = max(pr.first,pr.second);
1612 for (
int i=0; i<ntrs; i++)
1613 tris[i] = tris[tris[i]];
1616 if (tracks.size() > 0)
1618 for (
int i=0; i<(int)tracks.size(); i++)
1620 if (tris[i] == i)
continue;
1622 ProjMap &tr0 = tracks[tris[i]].projections;
1623 ProjMap &tr1 = tracks[i].projections;
1625 for(ProjMap::iterator itr1 = tr1.begin(); itr1 != tr1.end(); itr1++)
1627 Proj &prj = itr1->second;
1638 for (
int i=0; i<(int)tracks.size(); i++)
1640 if (tris[i] != i)
continue;
1641 if (n == i)
continue;
1642 tracks[n] = tracks[i];
1643 tracks[n].point = tracks[i].point;
1660 int SysSBA::mergeTracksSt(
int tri0,
int tri1)
1663 ProjMap tr0 = tracks[tri0].projections;
1664 ProjMap &tr1 = tracks[tri1].projections;
1666 for(ProjMap::iterator itr = tr1.begin(); itr != tr1.end(); itr++)
1668 Proj &prj = itr->second;
1669 bool ok = addProj(prj.
ndi, tri0, prj.
kp, prj.
stereo);
1672 tracks[tri0].projections = tr0;
void setKcam(const fc::CamParams &cp)
Sets the Kcam and baseline matrices from frame_common::CamParams.
void setDr(bool local=false)
Set angle derivates.
void normRot()
Normalize quaternion to unit. Problem with global derivatives near w=0, solved by a hack for now...
Eigen::Matrix< double, 3, 6 > Hpc
Point-to-camera Hessian (JpT*Jc)
Eigen::Vector3d plane_local_normal
Original normal in plane_node_index coordinate's frame.
double calcErr(const Node &nd, const Point &pt, double huber=0.0)
Calculates re-projection error and stores it in err.
std::map< const int, Proj, std::less< int >, Eigen::aligned_allocator< Proj > > ProjMap
Eigen::Quaternion< double > oldqrot
Previous quaternion rotation, saved for downdating within LM.
int F77_FUNC() dpotrf(char *uplo, int *n, double *a, int *lda, int *info)
Eigen::Matrix< double, 6, 6 > Hcc
Camera-to-camera Hessian (JcT*Jc)
void setJacobians(const Node &nd, const Point &pt, JacobProds *jpp)
Sets the jacobians and hessians for the projection to use for SBA.
int F77_FUNC() dpotrs(char *uplo, int *n, int *nrhs, double *a, int *lda, double *b, int *ldb, int *info)
Eigen::Matrix< double, 3, 3 > Hpp
Point-to-point Hessian (JpT*Jp).
Eigen::Vector3d err
Reprojection error.
bool isFixed
For SBA, is this camera fixed or free?
Eigen::Matrix< double, 3, 1 > Bp
The B matrix with respect to points (JpT*Err)
int plane_point_index
Point-plane match point index in SBA.
Eigen::Matrix< double, 4, 1 > oldtrans
Previous translation, saved for downdating within LM.
NODE holds graph nodes corresponding to frames, for use in sparse bundle adjustment. Each node has a 6DOF pose, encoded as a translation vector and rotation unit quaternion (Eigen classes). These represent the pose of the node in the world frame.
int plane_node_index
Point-plane node index in SBA.
Eigen::Matrix< double, 6, 3 > Tpc
int F77_FUNC() dpotri(char *uplo, int *n, double *a, int *lda, int *info)
Eigen::Matrix< double, 6, 1 > JcTE
Another matrix with respect to cameras (JcT*Err)
bool stereo
Whether the projection is Stereo (True) or Monocular (False).
double getErrNorm()
Get the correct norm of the error, depending on whether the projection is monocular or stereo...
Proj holds a projection measurement of a point onto a frame. They are a repository for the link betwe...
Eigen::Quaternion< double > qrot
Rotation of the node expressed as a Quaternion.
int F77_FUNC() dpotf2(char *uplo, int *n, double *a, int *lda, int *info)
int ndi
Node index, the camera node for this projection.
Eigen::Vector3d plane_point
Point for point-plane projections.
bool isValid
valid or not (could be out of bounds)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Matrix< double, 4, 1 > trans
Translation in homogeneous coordinates, last element is 1.0.
void setTransform()
Sets the transform matrices of the node.
Eigen::Vector3d kp
Keypoint, u,v,u-d vector.
double getErrSquaredNorm()
Get the correct squared norm of the error, depending on whether the projection is monocular or stereo...
JacobProds * jp
Jacobian products.
bool pointPlane
Whether this is a point-plane match (true) or a point-point match (false).
Eigen::Vector4d Point
Point holds 3D points using in world coordinates. Currently we just represent these as 4-vectors...
#define SBA_BLOCK_JACOBIAN_PCG
Eigen::Vector3d plane_normal
Normal for point-plane projections.