54 #include <Eigen/Cholesky> 56 using namespace Eigen;
69 gettimeofday(&tv,
nullptr);
70 long long ts = tv.tv_sec;
93 cout <<
"Can't open file " << fname << endl;
100 if (!getline(ifs,line) || line !=
"# P2 Constraint File")
102 cout <<
"Bad header" << endl;
105 cout <<
"Found P2 constraint file" << endl;
108 int ncams, nss, nscs, np2s;
109 if (!(ifs >> ncams >> nss >> np2s >> nscs))
111 cout <<
"Bad entity count" << endl;
114 cout <<
"Number of cameras: " << ncams
115 <<
" Number of scalers: " << nss
116 <<
" Number of p2p constraints: " << np2s
117 <<
" Number of scale constraints: " << nscs << endl;
119 cout <<
"Reading in camera data..." << flush;
120 std::vector<Node,Eigen::aligned_allocator<Node> > &nodes = spa.
nodes;
123 for (
int i=0; i<ncams; i++)
126 if (!(ifs >> v1 >> v2 >> v3))
128 cout <<
"Bad node translation params at number " << i << endl;
131 nd.
trans = Vector4d(v1,v2,v3,1.0);
133 if (!(ifs >> v1 >> v2 >> v3))
135 cout <<
"Bad node rotation quaternion at number " << i << endl;
139 nd.
qrot = Quaternion<double>(v1,v2,v2,0.0);
144 cout <<
"done" << endl;
147 cout <<
"Reading in constraint data..." << flush;
148 std::vector<ConP2,Eigen::aligned_allocator<ConP2> > &cons = spa.
p2cons;
151 for (
int i=0; i<np2s; i++)
157 if (!(ifs >> p1 >> p2))
159 cout <<
"Bad node indices at constraint " << i << endl;
163 for (
int i=0; i<6; i++)
167 cout <<
"Bad constraint mean at constraint " << i << endl;
172 for (
int i=0; i<36; i++)
176 cout <<
"Bad constraint precision at constraint " << i << endl;
185 con.
prec = Matrix<double,6,6>(vv);
192 cout <<
"Reading in scale constraint data..." << flush;
193 std::vector<ConScale,Eigen::aligned_allocator<ConScale> > &scons = spa.
scons;
196 for (
int i=0; i<nscs; i++)
201 if (!(ifs >> p1 >> p2 >> sv >> ks >> w))
203 cout <<
"Bad scale constraint at constraint " << i << endl;
213 scons.push_back(scon);
225 void ConP2::setJacobians(std::vector<
Node,Eigen::aligned_allocator<Node> > &nodes)
228 Node &nr = nodes[ndr];
229 Matrix<double,4,1> &tr = nr.
trans;
230 Quaternion<double> &qr = nr.
qrot;
231 Node &n1 = nodes[nd1];
232 Matrix<double,4,1> &t1 = n1.
trans;
233 Quaternion<double> &q1 = n1.
qrot;
236 Eigen::Matrix<double,3,1> pc = nr.
w2n * t1;
242 J0.block<3,3>(0,0) = -nr.
w2n.block<3,3>(0,0);
247 Eigen::Matrix<double,3,1> pwt;
248 pwt = (t1-tr).head(3);
251 Eigen::Matrix<double,3,1> dp = nr.
dRdx * pwt;
252 J0.block<3,1>(0,3) = dp;
255 J0.block<3,1>(0,4) = dp;
258 J0.block<3,1>(0,5) = dp;
261 J0.block<3,3>(3,0).setZero();
267 Eigen::Quaternion<double> qr0, qr1, qrn, qrd;
268 qr1.coeffs() = q1.coeffs();
269 qrn.coeffs() = Vector4d(-qpmean.w(),-qpmean.z(),qpmean.y(),qpmean.x());
270 qr0.coeffs() = Vector4d(-qr.x(),-qr.y(),-qr.z(),qr.w());
277 qrn.vec() = -qrn.vec();
280 J0.block<3,1>(3,3) = qrn.vec();
283 qrn.coeffs() = Vector4d(qpmean.z(),-qpmean.w(),-qpmean.x(),qpmean.y());
288 qrn.vec() = -qrn.vec();
291 J0.block<3,1>(3,4) = qrn.vec();
294 qrn.coeffs() = Vector4d(-qpmean.y(),qpmean.x(),-qpmean.w(),qpmean.z());
299 qrn.vec() = -qrn.vec();
302 J0.block<3,1>(3,5) = qrn.vec();
305 J0t = J0.transpose();
312 J1.block<3,3>(0,0) = nr.
w2n.block<3,3>(0,0);
315 J1.block<3,3>(0,3).setZero();
318 J1.block<3,3>(3,0).setZero();
324 Eigen::Quaternion<double> qrc;
325 qrc.coeffs() = Vector4d(-qr.x(),-qr.y(),-qr.z(),qr.w());
326 qrc = qpmean*qrc*qr1;
332 double wdq = 1.0 - dq*dq;
333 qr1.coeffs() = Vector4d(dq,0,0,wdq);
338 qrn.coeffs() = Vector4d(1,0,0,0);
345 qrn.vec() = -qrn.vec();
348 J1.block<3,1>(3,3) = qrn.vec();
351 qrn.coeffs() = Vector4d(0,1,0,0);
356 qrn.vec() = -qrn.vec();
359 J1.block<3,1>(3,4) = qrn.vec();
362 qrn.coeffs() = Vector4d(0,0,1,0);
367 qrn.vec() = -qrn.vec();
370 J1.block<3,1>(3,5) = qrn.vec();
373 J1t = J1.transpose();
384 void ConScale::setJacobians(std::vector<
Node,Eigen::aligned_allocator<Node> > &nodes)
387 Node &n0 = nodes[nd0];
388 Matrix<double,4,1> &t0 = n0.
trans;
389 Node &n1 = nodes[nd1];
390 Matrix<double,4,1> &t1 = n1.
trans;
392 Eigen::Matrix<double,3,1> td = (t1-t0).head(3);
412 void ConP3P::setJacobians(std::vector<
Node,Eigen::aligned_allocator<Node> > nodes)
415 Node nr = nodes[ndr];
416 Matrix<double,4,1> &tr = nr.
trans;
417 Quaternion<double> &qr = nr.
qrot;
418 Node n1 = nodes[nd1];
419 Matrix<double,4,1> &t1 = n1.
trans;
420 Quaternion<double> &q1 = n1.
qrot;
421 Node n2 = nodes[nd2];
422 Matrix<double,4,1> &t2 = n2.
trans;
423 Quaternion<double> &q2 = n2.
qrot;
431 J10.block<3,3>(0,0) = -nr.
w2n.block<3,3>(0,0);
435 Matrix<double,3,1> pwt = (t1-tr).head(3);
436 Matrix<double,3,1> dp = nr.
dRdx * pwt;
437 J10.block<3,1>(0,3) = dp;
439 J10.block<3,1>(0,4) = dp;
441 J10.block<3,1>(0,5) = dp;
444 J10.block<3,3>(3,0).setZero();
450 double wn = -1.0/qr.w();
451 dp[0] = wn*t1[0]*qr.x() - t1[3];
452 dp[1] = wn*t1[1]*qr.x() + t1[2];
453 dp[2] = wn*t1[2]*qr.x() - t1[1];
454 J10.block<3,1>(3,3) = dp;
457 dp[0] = wn*t1[0]*qr.y() - t1[2];
458 dp[1] = wn*t1[1]*qr.y() - t1[3];
459 dp[2] = wn*t1[2]*qr.y() + t1[0];
460 J10.block<3,1>(3,4) = dp;
463 dp[0] = wn*t1[0]*qr.z() + t1[1];
464 dp[1] = wn*t1[1]*qr.z() - t1[0];
465 dp[2] = wn*t1[2]*qr.z() - t1[3];
466 J10.block<3,1>(3,5) = dp;
473 J20.block<3,3>(0,0) = -nr.
w2n.block<3,3>(0,0);
477 pwt = (t2-tr).head(3);
479 J20.block<3,1>(0,3) = dp;
481 J20.block<3,1>(0,4) = dp;
483 J20.block<3,1>(0,5) = dp;
486 J20.block<3,3>(3,0).setZero();
493 dp[0] = wn*q2.x()*qr.x() - q2.w();
494 dp[1] = wn*q2.y()*qr.x() + q2.z();
495 dp[2] = wn*q2.z()*qr.x() - q2.y();
496 J20.block<3,1>(3,3) = dp;
499 dp[0] = wn*q2.x()*qr.y() - q2.z();
500 dp[1] = wn*q2.y()*qr.y() - q2.w();
501 dp[2] = wn*q2.z()*qr.y() + q2.x();
502 J20.block<3,1>(3,4) = dp;
505 dp[0] = wn*q2.x()*qr.z() + q2.y();
506 dp[1] = wn*q2.y()*qr.z() - q2.x();
507 dp[2] = wn*q2.z()*qr.z() - q2.w();
508 J20.block<3,1>(3,5) = dp;
516 J11.block<3,3>(0,0) = nr.
w2n.block<3,3>(0,0);
519 J11.block<3,3>(0,3).setZero();
522 J11.block<3,3>(3,0).setZero();
529 dp[0] = wn*qr.x()*q1.x() + qr.w();
530 dp[1] = wn*qr.y()*q1.x() - qr.z();
531 dp[2] = wn*qr.z()*q1.x() + qr.y();
532 J11.block<3,1>(3,3) = dp;
535 dp[0] = wn*qr.x()*q1.y() + qr.z();
536 dp[1] = wn*qr.y()*q1.y() + qr.w();
537 dp[2] = wn*qr.z()*q1.y() - qr.x();
538 J11.block<3,1>(3,4) = dp;
541 dp[0] = wn*qr.x()*q1.z() - qr.y();
542 dp[1] = wn*qr.y()*q1.z() + qr.x();
543 dp[2] = wn*qr.z()*q1.z() + qr.w();
544 J11.block<3,1>(3,5) = dp;
554 J22.block<3,3>(0,0) = nr.
w2n.block<3,3>(0,0);
557 J22.block<3,3>(0,3).setZero();
560 J22.block<3,3>(3,0).setZero();
567 dp[0] = wn*qr.x()*q2.x() + qr.w();
568 dp[1] = wn*qr.y()*q2.x() - qr.z();
569 dp[2] = wn*qr.z()*q2.x() + qr.y();
570 J22.block<3,1>(3,3) = dp;
573 dp[0] = wn*qr.x()*q2.y() + qr.z();
574 dp[1] = wn*qr.y()*q2.y() + qr.w();
575 dp[2] = wn*qr.z()*q2.y() - qr.x();
576 J22.block<3,1>(3,4) = dp;
579 dp[0] = wn*qr.x()*q2.z() - qr.y();
580 dp[1] = wn*qr.y()*q2.z() + qr.x();
581 dp[2] = wn*qr.z()*q2.z() + qr.w();
582 J22.block<3,1>(3,5) = dp;
590 inline double ConP2::calcErr(
const Node &nd0,
const Node &nd1)
592 Quaternion<double> q0p,q1;
593 q0p.vec() = -nd0.
qrot.coeffs().head(3);
594 q0p.w() = nd0.
qrot.w();
596 err.block<3,1>(0,0) = nd0.
w2n * nd1.
trans - tmean;
603 q1 = qpmean * q0p * q1;
610 err.block<3,1>(3,0) = -q1.vec();
613 err.block<3,1>(3,0) = q1.vec();
615 return err.dot(prec * err);
620 double ConP2::calcErrDist(
const Node &nd0,
const Node &nd1)
623 Quaternion<double> q0p,q1;
624 q0p.vec() = -nd0.
qrot.vec();
625 q0p.w() = nd0.
qrot.w();
628 return derr.dot(derr);
633 inline double ConScale::calcErr(
const Node &nd0,
const Node &nd1,
double alpha)
644 int SysSPA::addNode(Eigen::Matrix<double,4,1> &trans,
645 Eigen::Quaternion<double> &qrot,
657 return nodes.size()-1;
666 bool SysSPA::addConstraint(
int nd0,
int nd1,
667 Eigen::Vector3d &tmean,
668 Eigen::Quaterniond &qpmean,
669 Eigen::Matrix<double,6,6> &prec)
671 if (nd0 >= (
int)nodes.size() || nd1 >= (int)nodes.size())
679 Quaternion<double> qr;
682 con.
qpmean = qr.inverse();
685 p2cons.push_back(con);
693 double SysSPA::calcCost(
bool tcost)
700 for(
size_t i=0; i<p2cons.size(); i++)
702 ConP2 &con = p2cons[i];
711 for(
size_t i=0; i<p2cons.size(); i++)
713 ConP2 &con = p2cons[i];
717 if (scons.size() > 0)
718 for(
size_t i=0; i<scons.size(); i++)
721 double err = con.
calcErr(nodes[con.
nd0],nodes[con.
nd1],scales[con.
sv]);
734 void SysSPA::setupSys(
double sLambda)
738 int nFree = nodes.size() - nFixed;
739 int nscales = scales.size();
740 A.setZero(6*nFree+nscales,6*nFree+nscales);
741 B.setZero(6*nFree+nscales);
742 VectorXi dcnt(nFree);
746 double lam = 1.0 + sLambda;
749 for(
size_t pi=0; pi<p2cons.size(); pi++)
751 ConP2 &con = p2cons[pi];
756 int i0 = 6*(con.
ndr-nFixed);
757 int i1 = 6*(con.
nd1-nFixed);
761 A.block<6,6>(i0,i0) += con.
J0t * con.
prec * con.
J0;
762 dcnt(con.
ndr - nFixed)++;
766 dcnt(con.
nd1 - nFixed)++;
767 Matrix<double,6,6> tp = con.
prec * con.
J1;
768 A.block<6,6>(i1,i1) += con.
J1t * tp;
771 A.block<6,6>(i0,i1) += con.
J0t * con.
prec * con.
J1;
772 A.block<6,6>(i1,i0) += con.
J1t * con.
prec * con.
J0;
778 B.block<6,1>(i0,0) -= con.
J0t * con.
prec * con.
err;
780 B.block<6,1>(i1,0) -= con.
J1t * con.
prec * con.
err;
784 if (scons.size() > 0)
785 for(
size_t pi=0; pi<scons.size(); pi++)
791 int i0 = 6*(con.
nd0-nFixed);
792 int i1 = 6*(con.
nd1-nFixed);
796 A.block<3,3>(i0,i0) += con.
w * con.
J0 * con.
J0.transpose();
800 A.block<3,3>(i1,i1) += con.
w * con.
J1 * con.
J1.transpose();
803 A.block<3,3>(i0,i1) += con.
w * con.
J0 * con.
J1.transpose();
804 A.block<3,3>(i1,i0) = A.block<3,3>(i0,i1).transpose();
810 B.block<3,1>(i0,0) -= con.
w * con.
J0 * con.
err;
812 B.block<3,1>(i1,0) -= con.
w * con.
J1 * con.
err;
815 int is = 6*nFree+con.
sv;
816 A(is,is) += con.
w * con.
ks * con.
ks;
819 A.block<3,1>(i0,is) += con.
w * con.
J0 * -con.
ks;
820 A.block<1,3>(is,i0) = A.block<3,1>(i0,is).transpose();
824 A.block<3,1>(i1,is) += con.
w * con.
J1 * -con.
ks;
825 A.block<1,3>(is,i1) = A.block<3,1>(i1,is).transpose();
829 B(is) -= con.
w * (-con.
ks) * con.
err;
838 for (
int i=0; i<6*nFree; i++)
839 for (
int j=0; j<6*nFree; j++)
840 if (std::isnan(A(i,j)) ) { printf(
"[SetupSys] NaN in A\n"); *(
int *)0x0 = 0; }
842 for (
int j=0; j<6*nFree; j++)
843 if (std::isnan(B[j]) ) { printf(
"[SetupSys] NaN in B\n"); *(
int *)0x0 = 0; }
846 for (
int i=0; i<nFree; i++)
847 if (dcnt(i) == 0) ndc++;
850 cout <<
"[SetupSys] " << ndc <<
" disconnected nodes" << endl;
856 void SysSPA::setupSparseSys(
double sLambda,
int iter,
int sparseType)
860 int nFree = nodes.size() - nFixed;
866 csp.setupBlockStructure(nFree);
868 csp.setupBlockStructure(0);
872 VectorXi dcnt(nFree);
876 double lam = 1.0 + sLambda;
879 for(
size_t pi=0; pi<p2cons.size(); pi++)
881 ConP2 &con = p2cons[pi];
885 int i0 = con.
ndr-nFixed;
886 int i1 = con.
nd1-nFixed;
890 Matrix<double,6,6> m = con.
J0t*con.
prec*con.
J0;
891 csp.addDiagBlock(m,i0);
892 dcnt(con.
ndr - nFixed)++;
896 dcnt(con.
nd1 - nFixed)++;
897 Matrix<double,6,6> tp = con.
prec * con.
J1;
898 Matrix<double,6,6> m = con.
J1t * tp;
899 csp.addDiagBlock(m,i1);
902 Matrix<double,6,6> m2 = con.
J0t * tp;
906 csp.addOffdiagBlock(m,i1,i0);
909 csp.addOffdiagBlock(m2,i0,i1);
915 csp.B.block<6,1>(i0*6,0) -= con.
J0t * con.
prec * con.
err;
917 csp.B.block<6,1>(i1*6,0) -= con.
J1t * con.
prec * con.
err;
924 csp.incDiagBlocks(lam);
926 csp.setupCSstructure(lam,iter==0);
934 for (
int i=0; i<nFree; i++)
935 if (dcnt(i) == 0) ndc++;
938 cout <<
"[SetupSparseSys] " << ndc <<
" disconnected nodes" << endl;
951 int SysSPA::doSPA(
int niter,
double sLambda,
int useCSparse,
double initTol,
955 int nFree = nodes.size() - nFixed;
958 int ncams = nodes.size();
960 int nscales = scales.size();
963 vector<double> oldscales;
964 oldscales.resize(nscales);
971 int ncons = p2cons.size();
974 for (
int i=0; i<ncams; i++)
989 sqMinDelta = 1e-8 * 1e-8;
990 double cost = calcCost();
992 cout << iter <<
" Initial squared cost: " << cost <<
" which is " 993 << sqrt(cost/ncons) <<
" rms error" << endl;
996 for (; iter<niter; iter++)
1002 long long t0, t1, t2, t3;
1005 setupSparseSys(lambda,iter,useCSparse);
1012 if (csp.B.rows() != 0)
1014 int iters = csp.doBPCG(maxCGiters,initTol,iter);
1016 cout <<
"[Block PCG] " << iters <<
" iterations" << endl;
1019 else if (useCSparse > 0)
1021 bool ok = csp.doChol();
1023 cout <<
"[DoSPA] Sparse Cholesky failed!" << endl;
1026 A.ldlt().solveInPlace(B);
1029 VectorXd &BB = useCSparse ? csp.B : B;
1033 double sqDiff = BB.squaredNorm();
1034 if (sqDiff < sqMinDelta)
1041 for(
int i=0; i < ncams; i++)
1043 Node &nd = nodes[i];
1047 nd.
trans.head<3>() += BB.segment<3>(ci);
1049 Quaternion<double> qr;
1050 qr.vec() = BB.segment<3>(ci+3);
1051 qr.w() = sqrt(1.0 - qr.vec().squaredNorm());
1053 Quaternion<double> qrn,qrx;
1058 nd.
qrot.coeffs() = -qr.coeffs();
1060 nd.
qrot.coeffs() = qr.coeffs();
1070 for(
int i=0; i < nscales; i++)
1072 oldscales[i] = scales[i];
1079 double newcost = calcCost();
1081 cout << iter <<
" Updated squared cost: " << newcost <<
" which is " 1082 << sqrt(newcost/ncons) <<
" rms error" << endl;
1098 for(
int i=0; i<ncams; i++)
1100 Node &nd = nodes[i];
1110 for(
int i=0; i < nscales; i++)
1111 scales[i] = oldscales[i];
1116 cout << iter <<
" Downdated cost: " << cost << endl;
1130 ofstream ofs(fname);
1133 cout <<
"Can't open file " << fname << endl;
1140 setupSparseSys(0.0,0,useCSparse);
1144 double *Ax = csp.A->x;
1146 for (
int i=0; i<csp.csize; i++)
1147 for (
int j=Ap[i]; j<Ap[i+1]; j++)
1149 ofs << Ai[j] <<
" " << i << setprecision(16) <<
" " << Ax[j] << endl;
1153 Eigen::IOFormat pfmt(16);
1155 int nrows = A.rows();
1156 int ncols = A.cols();
1158 for (
int i=0; i<nrows; i++)
1159 for (
int j=i; j<ncols; j++)
1163 ofs << i <<
" " << j << setprecision(16) <<
" " << a << endl;
1172 void SysSPA::spanningTree(
int node)
1174 int nnodes = nodes.size();
1177 vector<vector<int> > cind;
1178 cind.resize(nnodes);
1180 for(
size_t pi=0; pi<p2cons.size(); pi++)
1182 ConP2 &con = p2cons[pi];
1185 cind[i0].push_back(i1);
1186 cind[i1].push_back(i0);
1190 VectorXd dist(nnodes);
1191 dist.setConstant(1e100);
1195 std::multimap<double,int> open;
1196 open.emplace(0.0,node);
1199 while (!open.empty())
1202 int ni = open.begin()->second;
1203 double di = open.begin()->first;
1204 open.erase(open.begin());
1205 if (di > dist[ni])
continue;
1208 Node &nd = nodes[ni];
1209 Matrix<double,3,4> n2w;
1212 vector<int> &nns = cind[ni];
1213 for (
int i=0; i<(int)nns.size(); i++)
1215 ConP2 &con = p2cons[nns[i]];
1216 double dd = con.
tmean.norm();
1221 Node &nd2 = nodes[nn];
1222 Vector3d tmean = con.
tmean;
1223 Quaterniond qpmean = con.
qpmean;
1226 qpmean = qpmean.inverse();
1227 tmean = nd.
qrot.toRotationMatrix().transpose()*nd2.
qrot.toRotationMatrix()*tmean;
1230 if (dist[nn] > di + dd)
1234 open.emplace(di+dd,nn);
1237 trans.head(3) = tmean;
1239 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.