54 #include <Eigen/Cholesky>    56 using namespace Eigen;
    68   gettimeofday(&tv,NULL);
    69   long long ts = tv.tv_sec;
    92         cout << 
"Can't open file " << fname << endl;
    99     if (!getline(ifs,line) || line != 
"# P2 Constraint File")
   101       cout << 
"Bad header" << endl;
   104     cout << 
"Found P2 constraint file" << endl;
   107     int ncams, nss, nscs, np2s;
   108     if (!(ifs >> ncams >> nss >> np2s >> nscs))
   110       cout << 
"Bad entity count" << endl;  
   113     cout << 
"Number of cameras: " << ncams 
   114          << 
"  Number of scalers: " << nss
   115          << 
"  Number of p2p constraints: " << np2s
   116          << 
"  Number of scale constraints: " << nscs << endl;
   118     cout << 
"Reading in camera data..." << flush;
   119     std::vector<Node,Eigen::aligned_allocator<Node> > &nodes = spa.
nodes;
   122     for (
int i=0; i<ncams; i++)
   125         if (!(ifs >> v1 >> v2 >> v3))
   127             cout << 
"Bad node translation params at number " << i << endl;
   130         nd.
trans = Vector4d(v1,v2,v3,1.0);
   132         if (!(ifs >> v1 >> v2 >> v3))
   134             cout << 
"Bad node rotation quaternion at number " << i << endl;
   138         nd.
qrot = Quaternion<double>(v1,v2,v2,0.0);
   143     cout << 
"done" << endl;
   146     cout << 
"Reading in constraint data..." << flush;
   147     std::vector<ConP2,Eigen::aligned_allocator<ConP2> > &cons = spa.
p2cons;
   150     for (
int i=0; i<np2s; i++)
   156         if (!(ifs >> p1 >> p2))
   158             cout << 
"Bad node indices at constraint " << i << endl;
   162         for (
int i=0; i<6; i++)
   166                 cout << 
"Bad constraint mean at constraint " << i << endl;
   171         for (
int i=0; i<36; i++)
   175                 cout << 
"Bad constraint precision at constraint " << i << endl;
   184         con.
prec = Matrix<double,6,6>(vv);
   191     cout << 
"Reading in scale constraint data..." << flush;
   192     std::vector<ConScale,Eigen::aligned_allocator<ConScale> > &scons = spa.
scons;
   195     for (
int i=0; i<nscs; i++)
   200         if (!(ifs >> p1 >> p2 >> sv >> ks >> w))
   202             cout << 
"Bad scale constraint at constraint " << i << endl;
   212         scons.push_back(scon);
   224   void ConP2::setJacobians(std::vector<
Node,Eigen::aligned_allocator<Node> > &nodes)
   227     Node &nr = nodes[ndr];
   228     Matrix<double,4,1> &tr = nr.
trans;
   229     Quaternion<double> &qr = nr.
qrot;
   230     Node &n1 = nodes[nd1];
   231     Matrix<double,4,1> &t1 = n1.
trans;
   232     Quaternion<double> &q1 = n1.
qrot;
   235     Eigen::Matrix<double,3,1> pc = nr.
w2n * t1;
   241     J0.block<3,3>(0,0) = -nr.
w2n.block<3,3>(0,0);
   246     Eigen::Matrix<double,3,1> pwt;
   247     pwt = (t1-tr).head(3);   
   250     Eigen::Matrix<double,3,1> dp = nr.
dRdx * pwt; 
   251     J0.block<3,1>(0,3) = dp;
   254     J0.block<3,1>(0,4) = dp;
   257     J0.block<3,1>(0,5) = dp;
   260     J0.block<3,3>(3,0).setZero();
   266     Eigen::Quaternion<double> qr0, qr1, qrn, qrd;
   267     qr1.coeffs() = q1.coeffs();
   268     qrn.coeffs() = Vector4d(-qpmean.w(),-qpmean.z(),qpmean.y(),qpmean.x());  
   269     qr0.coeffs() = Vector4d(-qr.x(),-qr.y(),-qr.z(),qr.w());
   276       qrn.vec() = -qrn.vec();
   279     J0.block<3,1>(3,3) = qrn.vec();
   282     qrn.coeffs() = Vector4d(qpmean.z(),-qpmean.w(),-qpmean.x(),qpmean.y());  
   287       qrn.vec() = -qrn.vec();
   290     J0.block<3,1>(3,4) = qrn.vec();
   293     qrn.coeffs() = Vector4d(-qpmean.y(),qpmean.x(),-qpmean.w(),qpmean.z());  
   298       qrn.vec() = -qrn.vec();
   301     J0.block<3,1>(3,5) = qrn.vec();
   304     J0t = J0.transpose();
   311     J1.block<3,3>(0,0) = nr.
w2n.block<3,3>(0,0);
   314     J1.block<3,3>(0,3).setZero();
   317     J1.block<3,3>(3,0).setZero();
   323     Eigen::Quaternion<double> qrc;
   324     qrc.coeffs() = Vector4d(-qr.x(),-qr.y(),-qr.z(),qr.w());
   325     qrc = qpmean*qrc*qr1;       
   331     double wdq = 1.0 - dq*dq;
   332     qr1.coeffs() = Vector4d(dq,0,0,wdq);
   337     qrn.coeffs() = Vector4d(1,0,0,0);
   344       qrn.vec() = -qrn.vec();
   347     J1.block<3,1>(3,3) = qrn.vec();
   350     qrn.coeffs() = Vector4d(0,1,0,0);
   355       qrn.vec() = -qrn.vec();
   358     J1.block<3,1>(3,4) = qrn.vec();
   361     qrn.coeffs() = Vector4d(0,0,1,0);
   366       qrn.vec() = -qrn.vec();
   369     J1.block<3,1>(3,5) = qrn.vec();
   372     J1t = J1.transpose();
   383   void ConScale::setJacobians(std::vector<
Node,Eigen::aligned_allocator<Node> > &nodes)
   386     Node &n0 = nodes[nd0];
   387     Matrix<double,4,1> &t0 = n0.
trans;
   388     Node &n1 = nodes[nd1];
   389     Matrix<double,4,1> &t1 = n1.
trans;
   391     Eigen::Matrix<double,3,1> td = (t1-t0).head(3);
   411   void ConP3P::setJacobians(std::vector<
Node,Eigen::aligned_allocator<Node> > nodes)
   414     Node nr = nodes[ndr];
   415     Matrix<double,4,1> &tr = nr.
trans;
   416     Quaternion<double> &qr = nr.
qrot;
   417     Node n1 = nodes[nd1];
   418     Matrix<double,4,1> &t1 = n1.
trans;
   419     Quaternion<double> &q1 = n1.
qrot;
   420     Node n2 = nodes[nd2];
   421     Matrix<double,4,1> &t2 = n2.
trans;
   422     Quaternion<double> &q2 = n2.
qrot;
   430     J10.block<3,3>(0,0) = -nr.
w2n.block<3,3>(0,0);
   434     Matrix<double,3,1> pwt = (t1-tr).head(3);
   435     Matrix<double,3,1> dp = nr.
dRdx * pwt; 
   436     J10.block<3,1>(0,3) = dp;
   438     J10.block<3,1>(0,4) = dp;
   440     J10.block<3,1>(0,5) = dp;
   443     J10.block<3,3>(3,0).setZero();
   449     double wn = -1.0/qr.w();  
   450     dp[0] = wn*t1[0]*qr.x() - t1[3];
   451     dp[1] = wn*t1[1]*qr.x() + t1[2];
   452     dp[2] = wn*t1[2]*qr.x() - t1[1];
   453     J10.block<3,1>(3,3) = dp;
   456     dp[0] = wn*t1[0]*qr.y() - t1[2];
   457     dp[1] = wn*t1[1]*qr.y() - t1[3];
   458     dp[2] = wn*t1[2]*qr.y() + t1[0];
   459     J10.block<3,1>(3,4) = dp;
   462     dp[0] = wn*t1[0]*qr.z() + t1[1];
   463     dp[1] = wn*t1[1]*qr.z() - t1[0];
   464     dp[2] = wn*t1[2]*qr.z() - t1[3];
   465     J10.block<3,1>(3,5) = dp;
   472     J20.block<3,3>(0,0) = -nr.
w2n.block<3,3>(0,0);
   476     pwt = (t2-tr).head(3);
   478     J20.block<3,1>(0,3) = dp;
   480     J20.block<3,1>(0,4) = dp;
   482     J20.block<3,1>(0,5) = dp;
   485     J20.block<3,3>(3,0).setZero();
   492     dp[0] = wn*q2.x()*qr.x() - q2.w();
   493     dp[1] = wn*q2.y()*qr.x() + q2.z();
   494     dp[2] = wn*q2.z()*qr.x() - q2.y();
   495     J20.block<3,1>(3,3) = dp;
   498     dp[0] = wn*q2.x()*qr.y() - q2.z();
   499     dp[1] = wn*q2.y()*qr.y() - q2.w();
   500     dp[2] = wn*q2.z()*qr.y() + q2.x();
   501     J20.block<3,1>(3,4) = dp;
   504     dp[0] = wn*q2.x()*qr.z() + q2.y();
   505     dp[1] = wn*q2.y()*qr.z() - q2.x();
   506     dp[2] = wn*q2.z()*qr.z() - q2.w();
   507     J20.block<3,1>(3,5) = dp;
   515     J11.block<3,3>(0,0) = nr.
w2n.block<3,3>(0,0);
   518     J11.block<3,3>(0,3).setZero();
   521     J11.block<3,3>(3,0).setZero();
   528     dp[0] = wn*qr.x()*q1.x() + qr.w();
   529     dp[1] = wn*qr.y()*q1.x() - qr.z();
   530     dp[2] = wn*qr.z()*q1.x() + qr.y();
   531     J11.block<3,1>(3,3) = dp;
   534     dp[0] = wn*qr.x()*q1.y() + qr.z();
   535     dp[1] = wn*qr.y()*q1.y() + qr.w();
   536     dp[2] = wn*qr.z()*q1.y() - qr.x();
   537     J11.block<3,1>(3,4) = dp;
   540     dp[0] = wn*qr.x()*q1.z() - qr.y();
   541     dp[1] = wn*qr.y()*q1.z() + qr.x();
   542     dp[2] = wn*qr.z()*q1.z() + qr.w();
   543     J11.block<3,1>(3,5) = dp;
   553     J22.block<3,3>(0,0) = nr.
w2n.block<3,3>(0,0);
   556     J22.block<3,3>(0,3).setZero();
   559     J22.block<3,3>(3,0).setZero();
   566     dp[0] = wn*qr.x()*q2.x() + qr.w();
   567     dp[1] = wn*qr.y()*q2.x() - qr.z();
   568     dp[2] = wn*qr.z()*q2.x() + qr.y();
   569     J22.block<3,1>(3,3) = dp;
   572     dp[0] = wn*qr.x()*q2.y() + qr.z();
   573     dp[1] = wn*qr.y()*q2.y() + qr.w();
   574     dp[2] = wn*qr.z()*q2.y() - qr.x();
   575     J22.block<3,1>(3,4) = dp;
   578     dp[0] = wn*qr.x()*q2.z() - qr.y();
   579     dp[1] = wn*qr.y()*q2.z() + qr.x();
   580     dp[2] = wn*qr.z()*q2.z() + qr.w();
   581     J22.block<3,1>(3,5) = dp;
   589   inline double ConP2::calcErr(
const Node &nd0, 
const Node &nd1)
   591       Quaternion<double> q0p,q1;
   592       q0p.vec()   = -nd0.
qrot.coeffs().head(3); 
   593       q0p.w()     =  nd0.
qrot.w();
   595       err.block<3,1>(0,0) = nd0.
w2n * nd1.
trans - tmean;
   602       q1 = qpmean * q0p * q1;
   609         err.block<3,1>(3,0) = -q1.vec(); 
   612         err.block<3,1>(3,0) = q1.vec(); 
   614       return err.dot(prec * err);
   619   double ConP2::calcErrDist(
const Node &nd0, 
const Node &nd1)
   622       Quaternion<double> q0p,q1;
   623       q0p.vec()   = -nd0.
qrot.vec(); 
   624       q0p.w()     =  nd0.
qrot.w();
   627       return derr.dot(derr);
   632   inline double ConScale::calcErr(
const Node &nd0, 
const Node &nd1, 
double alpha)
   643   int SysSPA::addNode(Eigen::Matrix<double,4,1> &trans, 
   644                       Eigen::Quaternion<double> &qrot,
   656     return nodes.size()-1;
   665   bool SysSPA::addConstraint(
int nd0, 
int nd1,
   666                              Eigen::Vector3d &tmean,
   667                              Eigen::Quaterniond &qpmean,
   668                              Eigen::Matrix<double,6,6> &prec)
   670     if (nd0 >= (
int)nodes.size() || nd1 >= (int)nodes.size()) 
   678     Quaternion<double> qr;
   681     con.
qpmean = qr.inverse(); 
   684     p2cons.push_back(con);
   692   double SysSPA::calcCost(
bool tcost)
   699         for(
size_t i=0; i<p2cons.size(); i++)
   701             ConP2 &con = p2cons[i];
   710         for(
size_t i=0; i<p2cons.size(); i++)
   712             ConP2 &con = p2cons[i];
   716         if (scons.size() > 0)       
   717           for(
size_t i=0; i<scons.size(); i++)
   720               double err = con.
calcErr(nodes[con.
nd0],nodes[con.
nd1],scales[con.
sv]);
   733   void SysSPA::setupSys(
double sLambda)
   737     int nFree = nodes.size() - nFixed;
   738     int nscales = scales.size();
   739     A.setZero(6*nFree+nscales,6*nFree+nscales);
   740     B.setZero(6*nFree+nscales);
   741     VectorXi dcnt(nFree);
   745     double lam = 1.0 + sLambda;
   748     for(
size_t pi=0; pi<p2cons.size(); pi++)
   750         ConP2 &con = p2cons[pi];
   755         int i0 = 6*(con.
ndr-nFixed); 
   756         int i1 = 6*(con.
nd1-nFixed); 
   760             A.block<6,6>(i0,i0) += con.
J0t * con.
prec * con.
J0;
   761             dcnt(con.
ndr - nFixed)++;
   765             dcnt(con.
nd1 - nFixed)++;
   766             Matrix<double,6,6> tp = con.
prec * con.
J1;
   767             A.block<6,6>(i1,i1) += con.
J1t * tp;
   770                 A.block<6,6>(i0,i1) += con.
J0t * con.
prec * con.
J1;
   771                 A.block<6,6>(i1,i0) += con.
J1t * con.
prec * con.
J0;
   777           B.block<6,1>(i0,0) -= con.
J0t * con.
prec * con.
err;
   779           B.block<6,1>(i1,0) -= con.
J1t * con.
prec * con.
err;
   783     if (scons.size() > 0)       
   784       for(
size_t pi=0; pi<scons.size(); pi++)
   790         int i0 = 6*(con.
nd0-nFixed); 
   791         int i1 = 6*(con.
nd1-nFixed); 
   795             A.block<3,3>(i0,i0) += con.
w * con.
J0 * con.
J0.transpose();
   799             A.block<3,3>(i1,i1) += con.
w * con.
J1 * con.
J1.transpose();
   802                 A.block<3,3>(i0,i1) += con.
w * con.
J0 * con.
J1.transpose();
   803                 A.block<3,3>(i1,i0) = A.block<3,3>(i0,i1).transpose();
   809           B.block<3,1>(i0,0) -= con.
w * con.
J0 * con.
err;
   811           B.block<3,1>(i1,0) -= con.
w * con.
J1 * con.
err;
   814         int is = 6*nFree+con.
sv;
   815         A(is,is) += con.
w * con.
ks * con.
ks;
   818             A.block<3,1>(i0,is) += con.
w * con.
J0 * -con.
ks;
   819             A.block<1,3>(is,i0) = A.block<3,1>(i0,is).transpose();
   823             A.block<3,1>(i1,is) += con.
w * con.
J1 * -con.
ks;
   824             A.block<1,3>(is,i1) = A.block<3,1>(i1,is).transpose();
   828         B(is) -= con.
w * (-con.
ks) * con.
err;
   837     for (
int i=0; i<6*nFree; i++)
   838       for (
int j=0; j<6*nFree; j++)
   839         if (isnan(A(i,j)) ) { printf(
"[SetupSys] NaN in A\n"); *(
int *)0x0 = 0; }
   841     for (
int j=0; j<6*nFree; j++)
   842       if (isnan(B[j]) ) { printf(
"[SetupSys] NaN in B\n"); *(
int *)0x0 = 0; }
   845     for (
int i=0; i<nFree; i++)
   846       if (dcnt(i) == 0) ndc++;
   849       cout << 
"[SetupSys] " << ndc << 
" disconnected nodes" << endl;
   855   void SysSPA::setupSparseSys(
double sLambda, 
int iter, 
int sparseType)
   859     int nFree = nodes.size() - nFixed;
   865       csp.setupBlockStructure(nFree); 
   867       csp.setupBlockStructure(0); 
   871     VectorXi dcnt(nFree);
   875     double lam = 1.0 + sLambda;
   878     for(
size_t pi=0; pi<p2cons.size(); pi++)
   880         ConP2 &con = p2cons[pi];
   884         int i0 = con.
ndr-nFixed; 
   885         int i1 = con.
nd1-nFixed; 
   889            Matrix<double,6,6> m = con.
J0t*con.
prec*con.
J0;
   890             csp.addDiagBlock(m,i0);
   891             dcnt(con.
ndr - nFixed)++;
   895             dcnt(con.
nd1 - nFixed)++;
   896             Matrix<double,6,6> tp = con.
prec * con.
J1;
   897             Matrix<double,6,6> m = con.
J1t * tp;
   898             csp.addDiagBlock(m,i1);
   901                 Matrix<double,6,6> m2 = con.
J0t * tp;
   905                     csp.addOffdiagBlock(m,i1,i0);
   908                   csp.addOffdiagBlock(m2,i0,i1);
   914           csp.B.block<6,1>(i0*6,0) -= con.
J0t * con.
prec * con.
err;
   916           csp.B.block<6,1>(i1*6,0) -= con.
J1t * con.
prec * con.
err;
   923       csp.incDiagBlocks(lam);   
   925       csp.setupCSstructure(lam,iter==0); 
   933     for (
int i=0; i<nFree; i++)
   934       if (dcnt(i) == 0) ndc++;
   937       cout << 
"[SetupSparseSys] " << ndc << 
" disconnected nodes" << endl;
   950   int SysSPA::doSPA(
int niter, 
double sLambda, 
int useCSparse, 
double initTol,
   954     int nFree = nodes.size() - nFixed; 
   957     int ncams = nodes.size();
   959     int nscales = scales.size();
   962     vector<double> oldscales;   
   963     oldscales.resize(nscales);
   970     int ncons = p2cons.size();
   973     for (
int i=0; i<ncams; i++)
   988     sqMinDelta = 1e-8 * 1e-8;
   989     double cost = calcCost();
   991       cout << iter << 
" Initial squared cost: " << cost << 
" which is "    992            << sqrt(cost/ncons) << 
" rms error" << endl; 
   995     for (; iter<niter; iter++)  
  1001         long long t0, t1, t2, t3;
  1004           setupSparseSys(lambda,iter,useCSparse); 
  1011             if (csp.B.rows() != 0)
  1013                 int iters = csp.doBPCG(maxCGiters,initTol,iter);
  1015                   cout << 
"[Block PCG] " << iters << 
" iterations" << endl;
  1018         else if (useCSparse > 0)
  1020             bool ok = csp.doChol();
  1022               cout << 
"[DoSPA] Sparse Cholesky failed!" << endl;
  1025           A.ldlt().solveInPlace(B); 
  1028         VectorXd &BB = useCSparse ? csp.B : B;
  1032         double sqDiff = BB.squaredNorm();
  1033         if (sqDiff < sqMinDelta) 
  1040         for(
int i=0; i < ncams; i++)
  1042             Node &nd = nodes[i];
  1046             nd.
trans.head<3>() += BB.segment<3>(ci);
  1048             Quaternion<double> qr;
  1049             qr.vec() = BB.segment<3>(ci+3); 
  1050             qr.w() = sqrt(1.0 - qr.vec().squaredNorm());
  1052             Quaternion<double> qrn,qrx;
  1057               nd.
qrot.coeffs() = -qr.coeffs();
  1059               nd.
qrot.coeffs() = qr.coeffs();
  1069           for(
int i=0; i < nscales; i++)
  1071               oldscales[i] = scales[i];
  1078         double newcost = calcCost();
  1080           cout << iter << 
" Updated squared cost: " << newcost << 
" which is "   1081            << sqrt(newcost/ncons) << 
" rms error" << endl;
  1097             for(
int i=0; i<ncams; i++)
  1099                 Node &nd = nodes[i];
  1109               for(
int i=0; i < nscales; i++)
  1110                 scales[i] = oldscales[i];
  1115               cout << iter << 
" Downdated cost: " << cost << endl;
  1129     ofstream ofs(fname);
  1132         cout << 
"Can't open file " << fname << endl;
  1139         setupSparseSys(0.0,0,useCSparse);
  1143         double *Ax = csp.A->x;
  1145         for (
int i=0; i<csp.csize; i++)
  1146           for (
int j=Ap[i]; j<Ap[i+1]; j++)
  1148               ofs << Ai[j] << 
" " << i << setprecision(16) << 
" " << Ax[j] << endl;
  1152         Eigen::IOFormat pfmt(16);
  1154         int nrows = A.rows();
  1155         int ncols = A.cols();
  1157         for (
int i=0; i<nrows; i++)
  1158           for (
int j=i; j<ncols; j++)
  1162                 ofs << i << 
" " << j << setprecision(16) << 
" " << a << endl;
  1171   void SysSPA::spanningTree(
int node)
  1173     int nnodes = nodes.size();
  1176     vector<vector<int> > cind;
  1177     cind.resize(nnodes);
  1179     for(
size_t pi=0; pi<p2cons.size(); pi++)
  1181         ConP2 &con = p2cons[pi];
  1184         cind[i0].push_back(i1);
  1185         cind[i1].push_back(i0);        
  1189     VectorXd dist(nnodes);
  1190     dist.setConstant(1e100);
  1194     multimap<double,int> open;  
  1195     open.insert(make_pair<double,int>(0.0,node));
  1198     while (!open.empty())
  1201         int ni = open.begin()->second;
  1202         double di = open.begin()->first;
  1203         open.erase(open.begin());
  1204         if (di > dist[ni]) 
continue; 
  1207         Node &nd = nodes[ni];
  1208         Matrix<double,3,4> n2w;
  1211         vector<int> &nns = cind[ni];
  1212         for (
int i=0; i<(int)nns.size(); i++)
  1214             ConP2 &con = p2cons[nns[i]];
  1215             double dd = con.
tmean.norm(); 
  1220             Node &nd2 = nodes[nn];
  1221             Vector3d tmean = con.
tmean;
  1222             Quaterniond qpmean = con.
qpmean;
  1225                 qpmean = qpmean.inverse();
  1226                 tmean = nd.
qrot.toRotationMatrix().transpose()*nd2.
qrot.toRotationMatrix()*tmean;
  1229             if (dist[nn] > di + dd) 
  1233                 open.insert(make_pair<double,int>(di+dd,nn));
  1236                 trans.head(3) = tmean;
  1238                 nd2.
trans.head(3) = n2w*trans;
 
void setDr(bool local=false)
Set angle derivates. 
SysSPA holds a set of nodes and constraints for sparse pose adjustment. 
void normRot()
Normalize quaternion to unit. Problem with global derivatives near w=0, solved by a hack for now...
double calcErrDist(const Node &nd0, const Node &nd1)
calculate error in distance only, no weighting 
Eigen::Matrix< double, 3, 3 > dRdx
Derivatives of the rotation matrix transpose wrt quaternion xyz, used for calculating Jacobian wrt po...
bool readP2File(char *fname, SysSPA spa)
constraint files 
void setJacobians(std::vector< Node, Eigen::aligned_allocator< Node > > &nodes)
Eigen::Quaternion< double > oldqrot
Previous quaternion rotation, saved for downdating within LM. 
Eigen::Matrix< double, 3, 3 > dRdy
Eigen::Matrix< double, 6, 6 > prec
Eigen::Matrix< double, 6, 6 > J1t
int nd1
Node index for the second node. 
Eigen::Matrix< double, 6, 6 > J1
bool isFixed
For SBA, is this camera fixed or free? 
Eigen::Vector3d tmean
Mean vector, quaternion (inverse) and precision matrix for this constraint. 
int nd1
Node index for the second node. 
void transformF2W(Eigen::Matrix< double, 3, 4 > &m, const Eigen::Matrix< double, 4, 1 > &trans, const Eigen::Quaternion< double > &qrot)
Eigen::Matrix< double, 4, 1 > oldtrans
Previous translation, saved for downdating within LM. 
double w
Weight for this constraint. 
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. 
Eigen::Matrix< double, 3, 4 > w2n
Resultant transform from world to node coordinates. 
Eigen::Matrix< double, 6, 6 > J0
jacobian with respect to frames; uses dR'/dq from Node calculation 
double calcErr(const Node &nd0, const Node &nd1, double alpha)
calculates projection error and stores it in <err> 
void writeSparseA(const char *fname, SysSBA &sba)
Eigen::Quaternion< double > qrot
Rotation of the node expressed as a Quaternion. 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Matrix< double, 4, 1 > trans
Translation in homogeneous coordinates, last element is 1.0. 
int sv
Scale variable index. 
std::vector< Node, Eigen::aligned_allocator< Node > > nodes
set of nodes (camera frames) for SPA system, indexed by position; 
void setTransform()
Sets the transform matrices of the node. 
void setJacobians(std::vector< Node, Eigen::aligned_allocator< Node > > &nodes)
jacobians are computed from (ti - tj)^2 - a*kij = 0 
Eigen::Matrix< double, 6, 1 > err
error 
double calcErr(const Node &nd0, const Node &nd1)
calculates projection error and stores it in <err> 
Eigen::Matrix< double, 3, 3 > dRdz
Eigen::Matrix< double, 6, 6 > J0t
#define SBA_BLOCK_JACOBIAN_PCG
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int nd0
Reference pose index. 
Eigen::Quaternion< double > qpmean
std::vector< ConP2, Eigen::aligned_allocator< ConP2 > > p2cons
Set of P2 constraints. 
double ks
Scale factor for this constraint. 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int ndr
Reference pose index. 
std::vector< ConScale, Eigen::aligned_allocator< ConScale > > scons
Set of scale constraints.