spa.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 //
36 // Sparse Pose Adjustment classes and functions
37 //
38 
39 //
40 // Ok, we're going with 2-pose constraints, and added scale variables.
41 // Format for files:
42 // Format for files:
43 // #nodes #scales #p2p_constraints #scale_constraints
44 // x y z rx ry rz ; first node, vector part of unit quaternion
45 // ...
46 // p1 p2 Lambda_12 ; first p2p constraint
47 // ...
48 // p1 p2 s1 K_12 w ; first scale constraint,
49 // ; (p1-p2)^2 = s1*K_12 with weight w
50 
51 
52 #include <stdio.h>
54 #include <Eigen/Cholesky>
55 
56 using namespace Eigen;
57 using namespace std;
58 
59 #include <iostream>
60 #include <iomanip>
61 #include <fstream>
62 #include <sys/time.h>
63 
64 // elapsed time in microseconds
65 static long long utime()
66 {
67  timeval tv;
68  gettimeofday(&tv,NULL);
69  long long ts = tv.tv_sec;
70  ts *= 1000000;
71  ts += tv.tv_usec;
72  return ts;
73 }
74 
75 namespace sba
76 {
77  // reads in a file of pose constraints
78  bool readP2File(char *fname, SysSPA spa)
79  {
80  // Format for files:
81  // #nodes #scales #p2p_constraints #scale_constraints
82  // x y z rx ry rz ; first node, vector part of unit quaternion
83  // ...
84  // p1 p2 Lambda_12 ; first p2p constraint
85  // ...
86  // p1 p2 s1 K_12 w ; first scale constraint,
87  // ; (p1-p2)^2 = s1*K_12 with weight w
88 
89  ifstream ifs(fname);
90  if (ifs == NULL)
91  {
92  cout << "Can't open file " << fname << endl;
93  return false;
94  }
95  ifs.precision(10); // what is this for???
96 
97  // read header
98  string line;
99  if (!getline(ifs,line) || line != "# P2 Constraint File")
100  {
101  cout << "Bad header" << endl;
102  return false;
103  }
104  cout << "Found P2 constraint file" << endl;
105 
106  // read number of cameras, scalers, and p2p constraints
107  int ncams, nss, nscs, np2s;
108  if (!(ifs >> ncams >> nss >> np2s >> nscs))
109  {
110  cout << "Bad entity count" << endl;
111  return false;
112  }
113  cout << "Number of cameras: " << ncams
114  << " Number of scalers: " << nss
115  << " Number of p2p constraints: " << np2s
116  << " Number of scale constraints: " << nscs << endl;
117 
118  cout << "Reading in camera data..." << flush;
119  std::vector<Node,Eigen::aligned_allocator<Node> > &nodes = spa.nodes;
120  Node nd;
121 
122  for (int i=0; i<ncams; i++)
123  {
124  double v1,v2,v3;
125  if (!(ifs >> v1 >> v2 >> v3))
126  {
127  cout << "Bad node translation params at number " << i << endl;
128  return false;
129  }
130  nd.trans = Vector4d(v1,v2,v3,1.0);
131 
132  if (!(ifs >> v1 >> v2 >> v3))
133  {
134  cout << "Bad node rotation quaternion at number " << i << endl;
135  return false;
136  }
137  Matrix3d m;
138  nd.qrot = Quaternion<double>(v1,v2,v2,0.0);
139  nd.normRot(); // normalize to unit vector and compute w
140 
141  nodes.push_back(nd);
142  }
143  cout << "done" << endl;
144 
145  // read in p2p constraints
146  cout << "Reading in constraint data..." << flush;
147  std::vector<ConP2,Eigen::aligned_allocator<ConP2> > &cons = spa.p2cons;
148  ConP2 con;
149 
150  for (int i=0; i<np2s; i++)
151  {
152  int p1, p2;
153  double vz[6]; // mean
154  double vv[36]; // prec
155 
156  if (!(ifs >> p1 >> p2))
157  {
158  cout << "Bad node indices at constraint " << i << endl;
159  return false;
160  }
161 
162  for (int i=0; i<6; i++)
163  {
164  if (!(ifs >> vz[i]))
165  {
166  cout << "Bad constraint mean at constraint " << i << endl;
167  return false;
168  }
169  }
170 
171  for (int i=0; i<36; i++)
172  {
173  if (!(ifs >> vv[i]))
174  {
175  cout << "Bad constraint precision at constraint " << i << endl;
176  return false;
177  }
178  }
179 
180  con.ndr = p1;
181  con.nd1 = p2;
182 
183  // con.setMean(Matrix<double,6,1>(vz));
184  con.prec = Matrix<double,6,6>(vv);
185 
186  cons.push_back(con);
187  }
188 
189 
190  // read in scale constraints
191  cout << "Reading in scale constraint data..." << flush;
192  std::vector<ConScale,Eigen::aligned_allocator<ConScale> > &scons = spa.scons;
193  ConScale scon;
194 
195  for (int i=0; i<nscs; i++)
196  {
197  int p1, p2, sv;
198  double ks, w;
199 
200  if (!(ifs >> p1 >> p2 >> sv >> ks >> w))
201  {
202  cout << "Bad scale constraint at constraint " << i << endl;
203  return false;
204  }
205 
206  scon.nd0 = p1;
207  scon.nd1 = p2;
208  scon.sv = sv;
209  scon.ks = ks;
210  scon.w = w;
211 
212  scons.push_back(scon);
213  }
214 
215  return true;
216  }
217 
218 // Do we want to normalize quaternion vectors based on the sign of w?
219 #define NORMALIZE_Q
220 
221  // set up Jacobians
222  // see Konolige RSS 2010 submission for details
223 
224  void ConP2::setJacobians(std::vector<Node,Eigen::aligned_allocator<Node> > &nodes)
225  {
226  // node references
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;
233 
234  // first get the second frame in first frame coords
235  Eigen::Matrix<double,3,1> pc = nr.w2n * t1;
236 
237  // Jacobians wrt first frame parameters
238 
239  // translational part of 0p1 wrt translational vars of p0
240  // this is just -R0' [from 0t1 = R0'(t1 - t0)]
241  J0.block<3,3>(0,0) = -nr.w2n.block<3,3>(0,0);
242 
243 
244  // translational part of 0p1 wrt rotational vars of p0
245  // dR'/dq * [pw - t]
246  Eigen::Matrix<double,3,1> pwt;
247  pwt = (t1-tr).head(3); // transform translations
248 
249  // dx
250  Eigen::Matrix<double,3,1> dp = nr.dRdx * pwt; // dR'/dq * [pw - t]
251  J0.block<3,1>(0,3) = dp;
252  // dy
253  dp = nr.dRdy * pwt; // dR'/dq * [pw - t]
254  J0.block<3,1>(0,4) = dp;
255  // dz
256  dp = nr.dRdz * pwt; // dR'/dq * [pw - t]
257  J0.block<3,1>(0,5) = dp;
258 
259  // rotational part of 0p1 wrt translation vars of p0 => zero
260  J0.block<3,3>(3,0).setZero();
261 
262  // rotational part of 0p1 wrt rotational vars of p0
263  // from 0q1 = qpmean * s0' * q0' * q1
264 
265  // dqdx
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()); // qpmean * ds0'/dx
269  qr0.coeffs() = Vector4d(-qr.x(),-qr.y(),-qr.z(),qr.w());
270  qr0 = qr0*qr1; // rotate to zero mean
271  qrd = qpmean*qr0; // for normalization check
272  qrn = qrn*qr0;
273 
274 #ifdef NORMALIZE_Q
275  if (qrd.w() < 0.0)
276  qrn.vec() = -qrn.vec();
277 #endif
278 
279  J0.block<3,1>(3,3) = qrn.vec();
280 
281  // dqdy
282  qrn.coeffs() = Vector4d(qpmean.z(),-qpmean.w(),-qpmean.x(),qpmean.y()); // qpmean * ds0'/dy
283  qrn = qrn*qr0;
284 
285 #ifdef NORMALIZE_Q
286  if (qrd.w() < 0.0)
287  qrn.vec() = -qrn.vec();
288 #endif
289 
290  J0.block<3,1>(3,4) = qrn.vec();
291 
292  // dqdz
293  qrn.coeffs() = Vector4d(-qpmean.y(),qpmean.x(),-qpmean.w(),qpmean.z()); // qpmean * ds0'/dz
294  qrn = qrn*qr0;
295 
296 #ifdef NORMALIZE_Q
297  if (qrd.w() < 0.0)
298  qrn.vec() = -qrn.vec();
299 #endif
300 
301  J0.block<3,1>(3,5) = qrn.vec();
302 
303  // transpose
304  J0t = J0.transpose();
305 
306  // cout << endl << "J0 " << ndr << endl << J0 << endl;
307 
308  // Jacobians wrt second frame parameters
309  // translational part of 0p1 wrt translational vars of p1
310  // this is just R0' [from 0t1 = R0'(t1 - t0)]
311  J1.block<3,3>(0,0) = nr.w2n.block<3,3>(0,0);
312 
313  // translational part of 0p1 wrt rotational vars of p1: zero
314  J1.block<3,3>(0,3).setZero();
315 
316  // rotational part of 0p1 wrt translation vars of p0 => zero
317  J1.block<3,3>(3,0).setZero();
318 
319 
320  // rotational part of 0p1 wrt rotational vars of p0
321  // from 0q1 = q0'*s1*q1
322 
323  Eigen::Quaternion<double> qrc;
324  qrc.coeffs() = Vector4d(-qr.x(),-qr.y(),-qr.z(),qr.w());
325  qrc = qpmean*qrc*qr1; // mean' * qr0' * qr1
326  qrc.normalize();
327 
328  // cout << endl << "QRC : " << qrc.coeffs().transpose() << endl;
329 
330  double dq = 1.0e-8;
331  double wdq = 1.0 - dq*dq;
332  qr1.coeffs() = Vector4d(dq,0,0,wdq);
333  // cout << "QRC+x: " << (qrc*qr1).coeffs().transpose() << endl;
334  // cout << "QRdx: " << ((qrc*qr1).coeffs().transpose() - qrc.coeffs().transpose())/dq << endl;
335 
336  // dqdx
337  qrn.coeffs() = Vector4d(1,0,0,0);
338  qrn = qrc*qrn;
339 
340  // cout << "J1dx: " << qrn.coeffs().transpose() << endl;
341 
342 #ifdef NORMALIZE_Q
343  if (qrc.w() < 0.0)
344  qrn.vec() = -qrn.vec();
345 #endif
346 
347  J1.block<3,1>(3,3) = qrn.vec();
348 
349  // dqdy
350  qrn.coeffs() = Vector4d(0,1,0,0);
351  qrn = qrc*qrn;
352 
353 #ifdef NORMALIZE_Q
354  if (qrc.w() < 0.0)
355  qrn.vec() = -qrn.vec();
356 #endif
357 
358  J1.block<3,1>(3,4) = qrn.vec();
359 
360  // dqdz
361  qrn.coeffs() = Vector4d(0,0,1,0);
362  qrn = qrc*qrn;
363 
364 #ifdef NORMALIZE_Q
365  if (qrc.w() < 0.0)
366  qrn.vec() = -qrn.vec();
367 #endif
368 
369  J1.block<3,1>(3,5) = qrn.vec();
370 
371  // transpose
372  J1t = J1.transpose();
373 
374  // cout << endl << "J1 " << nd1 << endl << J1 << endl;
375 
376  };
377 
378 
379 
380  // set up Jacobians
381  // see Konolige RSS 2010 submission for details
382 
383  void ConScale::setJacobians(std::vector<Node,Eigen::aligned_allocator<Node> > &nodes)
384  {
385  // node references
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;
390 
391  Eigen::Matrix<double,3,1> td = (t1-t0).head(3);
392 
393  // Jacobians wrt first frame parameters
394  // (ti - tj)^2 - a*kij
395 
396  // scale error wrt translational vars t0
397  J0 = -2.0 * td;
398 
399  // scale error wrt translational vars t1
400  J1 = 2.0 * td;
401 
402  // scale error wrt scale variable is just -kij
403  };
404 
405 
406 
407  //
408  // This hasn't been tested, and is probably wrong.
409  //
410 
411  void ConP3P::setJacobians(std::vector<Node,Eigen::aligned_allocator<Node> > nodes)
412  {
413  // node references
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;
423 
424  // calculate J10 -> d(0p1)/d(p0)
425  // rows are indexed by 0p1 parameters
426  // cols are indexed by p0 parameters
427 
428  // translational part of 0p1 wrt translational vars of p0
429  // this is just -R0' [from 0t1 = R0'(t1 - t0)]
430  J10.block<3,3>(0,0) = -nr.w2n.block<3,3>(0,0);
431 
432  // translational part of 0p1 wrt rotational vars of p0
433  // dR'/dq * [pw - t]
434  Matrix<double,3,1> pwt = (t1-tr).head(3);
435  Matrix<double,3,1> dp = nr.dRdx * pwt; // dR'/dqx * [pw - t]
436  J10.block<3,1>(0,3) = dp;
437  dp = nr.dRdy * pwt; // dR'/dqy * [pw - t]
438  J10.block<3,1>(0,4) = dp;
439  dp = nr.dRdz * pwt; // dR'/dqz * [pw - t]
440  J10.block<3,1>(0,5) = dp;
441 
442  // rotational part of 0p1 wrt translation vars of p0 => zero
443  J10.block<3,3>(3,0).setZero();
444 
445  // rotational part of 0p1 wrt rotational vars of p0
446  // from 0q1 = q0'*q1
447 
448  // dqdx
449  double wn = -1.0/qr.w(); // need to switch params for small qr(3)
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;
454 
455  // dqdy
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;
460 
461  // dqdz
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;
466 
467  // whew, J10 done...
468 
469  // J20 is similar, just using p2
470  // translational part of 0p2 wrt translational vars of p0
471  // this is just -R0' [from 0t2 = R0'(t2 - t0)]
472  J20.block<3,3>(0,0) = -nr.w2n.block<3,3>(0,0);
473 
474  // translational part of 0p2 wrt rotational vars of p0
475  // dR'/dq * [pw - t]
476  pwt = (t2-tr).head(3);
477  dp = nr.dRdx * pwt; // dR'/dqx * [pw - t]
478  J20.block<3,1>(0,3) = dp;
479  dp = nr.dRdy * pwt; // dR'/dqy * [pw - t]
480  J20.block<3,1>(0,4) = dp;
481  dp = nr.dRdz * pwt; // dR'/dqz * [pw - t]
482  J20.block<3,1>(0,5) = dp;
483 
484  // rotational part of 0p1 wrt translation vars of p0 => zero
485  J20.block<3,3>(3,0).setZero();
486 
487  // rotational part of 0p2 wrt rotational vars of p0
488  // from 0q1 = q0'*q2
489 
490  // dqdx
491  wn = -1.0/qr.w(); // need to switch params for small qr(3)
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;
496 
497  // dqdy
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;
502 
503  // dqdz
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;
508 
509  // calculate J11 -> d(0p1)/d(p1)
510  // rows are indexed by 0p1 parameters
511  // cols are indexed by p1 parameters
512 
513  // translational part of 0p1 wrt translational vars of p1
514  // this is just R0' [from 0t1 = R0'(t1 - t0)]
515  J11.block<3,3>(0,0) = nr.w2n.block<3,3>(0,0);
516 
517  // translational part of 0p1 wrt rotational vars of p1 => zero
518  J11.block<3,3>(0,3).setZero();
519 
520  // rotational part of 0p1 wrt translation vars of p1 => zero
521  J11.block<3,3>(3,0).setZero();
522 
523  // rotational part of 0p1 wrt rotational vars of p1
524  // from 0q1 = q0'*q1
525 
526  // dqdx1
527  wn = 1.0/q1.w(); // need to switch params for small q1(3)
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;
532 
533  // dqdy1
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;
538 
539  // dqdz1
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;
544 
545  // whew, J11 done...
546 
547  // J22 is similar to J11
548  // rows are indexed by 0p2 parameters
549  // cols are indexed by p2 parameters
550 
551  // translational part of 0p2 wrt translational vars of p2
552  // this is just R0' [from 0t2 = R0'(t2 - t0)]
553  J22.block<3,3>(0,0) = nr.w2n.block<3,3>(0,0);
554 
555  // translational part of 0p2 wrt rotational vars of p2 => zero
556  J22.block<3,3>(0,3).setZero();
557 
558  // rotational part of 0p2 wrt translation vars of p2 => zero
559  J22.block<3,3>(3,0).setZero();
560 
561  // rotational part of 0p2 wrt rotational vars of p2
562  // from 0q2 = q0'*q2
563 
564  // dqdx2
565  wn = 1.0/q2.w(); // need to switch params for small q2.w()
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;
570 
571  // dqdy1
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;
576 
577  // dqdz1
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;
582 
583  // whew, J22 done...
584 
585  };
586 
587 
588  // error function
589  inline double ConP2::calcErr(const Node &nd0, const Node &nd1)
590  {
591  Quaternion<double> q0p,q1;
592  q0p.vec() = -nd0.qrot.coeffs().head(3); // invert quaternion
593  q0p.w() = nd0.qrot.w();
594  q1 = nd1.qrot;
595  err.block<3,1>(0,0) = nd0.w2n * nd1.trans - tmean;
596 
597  // cout << endl;
598  // cout << q0p.coeffs().transpose() << endl;
599  // cout << q1.coeffs().transpose() << endl;
600  // cout << qpmean.coeffs().transpose() << endl;
601 
602  q1 = qpmean * q0p * q1;
603 
604  // cout << q1.coeffs().transpose() << endl << endl;
605 
606 // this seems to mess up convergence...
607 #ifdef NORMALIZE_Q
608  if (q1.w() < 0.0)
609  err.block<3,1>(3,0) = -q1.vec(); // normalized
610  else
611 #endif
612  err.block<3,1>(3,0) = q1.vec(); // do we have to normalize w???
613  // cout << endl << "Error: " << err.transpose() << endl << endl;
614  return err.dot(prec * err);
615  }
616 
617 
618  // error function for distance cost
619  double ConP2::calcErrDist(const Node &nd0, const Node &nd1)
620  {
621  Vector3d derr;
622  Quaternion<double> q0p,q1;
623  q0p.vec() = -nd0.qrot.vec(); // invert quaternion
624  q0p.w() = nd0.qrot.w();
625  q1 = nd1.qrot;
626  derr = nd0.w2n * nd1.trans - tmean;
627  return derr.dot(derr);
628  }
629 
630 
631  // error function
632  inline double ConScale::calcErr(const Node &nd0, const Node &nd1, double alpha)
633  {
634  err = (nd1.trans - nd0.trans).squaredNorm();
635  err -= ks*alpha;
636  // cout << "Scale err: " << err << endl;
637  return w*err*err;
638  }
639 
640 
641  // Adds a node to the system.
642  // \return the index of the node added.
643  int SysSPA::addNode(Eigen::Matrix<double,4,1> &trans,
644  Eigen::Quaternion<double> &qrot,
645  bool isFixed)
646  {
647  Node nd;
648  nd.trans = trans;
649  nd.qrot = qrot;
650  nd.isFixed = isFixed;
651  nd.setTransform(); // set up world2node transform
652  nd.setDr(true); // set rotational derivatives
653  // Should this be local or global?
654  nd.normRot();//Local();
655  nodes.push_back(nd);
656  return nodes.size()-1;
657  }
658 
659 
660  // add a constraint
661  // <nd0>, <nd1> are node id's
662  // <mean> is x,y,th, with th in radians
663  // <prec> is a 3x3 precision matrix (inverse covariance
664  // returns true if nodes are found
665  bool SysSPA::addConstraint(int nd0, int nd1,
666  Eigen::Vector3d &tmean,
667  Eigen::Quaterniond &qpmean,
668  Eigen::Matrix<double,6,6> &prec)
669  {
670  if (nd0 >= (int)nodes.size() || nd1 >= (int)nodes.size())
671  return false;
672 
673  ConP2 con;
674  con.ndr = nd0;
675  con.nd1 = nd1;
676 
677  con.tmean = tmean;
678  Quaternion<double> qr;
679  qr = qpmean;
680  qr.normalize();
681  con.qpmean = qr.inverse(); // inverse of the rotation measurement
682  con.prec = prec;
683 
684  p2cons.push_back(con);
685  return true;
686  }
687 
688 
689  // error measure, squared
690  // assumes node transforms have already been calculated
691  // <tcost> is true if we just want the distance offsets
692  double SysSPA::calcCost(bool tcost)
693  {
694  double cost = 0.0;
695 
696  // do distance offset
697  if (tcost)
698  {
699  for(size_t i=0; i<p2cons.size(); i++)
700  {
701  ConP2 &con = p2cons[i];
702  double err = con.calcErrDist(nodes[con.ndr],nodes[con.nd1]);
703  cost += err;
704  }
705  }
706 
707  // full cost
708  else
709  {
710  for(size_t i=0; i<p2cons.size(); i++)
711  {
712  ConP2 &con = p2cons[i];
713  double err = con.calcErr(nodes[con.ndr],nodes[con.nd1]);
714  cost += err;
715  }
716  if (scons.size() > 0) // can have zero scale constraints
717  for(size_t i=0; i<scons.size(); i++)
718  {
719  ConScale &con = scons[i];
720  double err = con.calcErr(nodes[con.nd0],nodes[con.nd1],scales[con.sv]);
721  cost += err;
722  }
723  }
724 
725  return cost;
726  }
727 
728 
729  // Set up linear system, from RSS submission (konolige 2010)
730  // This is a relatively compact version of the algorithm!
731  // but not Jacobians
732 
733  void SysSPA::setupSys(double sLambda)
734  {
735  // set matrix sizes and clear
736  // assumes scales vars are all free
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);
742  dcnt.setZero(nFree);
743 
744  // lambda augmentation
745  double lam = 1.0 + sLambda;
746 
747  // loop over P2 constraints
748  for(size_t pi=0; pi<p2cons.size(); pi++)
749  {
750  ConP2 &con = p2cons[pi];
751  con.setJacobians(nodes);
752 
753  // add in 4 blocks of A; actually just need upper triangular
754  // i0 < i1
755  int i0 = 6*(con.ndr-nFixed); // will be negative if fixed
756  int i1 = 6*(con.nd1-nFixed); // will be negative if fixed
757 
758  if (i0>=0)
759  {
760  A.block<6,6>(i0,i0) += con.J0t * con.prec * con.J0;
761  dcnt(con.ndr - nFixed)++;
762  }
763  if (i1>=0)
764  {
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;
768  if (i0>=0)
769  {
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;
772  }
773  }
774 
775  // add in 2 blocks of B
776  if (i0>=0)
777  B.block<6,1>(i0,0) -= con.J0t * con.prec * con.err;
778  if (i1>=0)
779  B.block<6,1>(i1,0) -= con.J1t * con.prec * con.err;
780  } // finish P2 constraints
781 
782  // loop over Scale constraints
783  if (scons.size() > 0) // could be zero
784  for(size_t pi=0; pi<scons.size(); pi++)
785  {
786  ConScale &con = scons[pi];
787  con.setJacobians(nodes);
788  // add in 4 blocks of A for t0, t1; actually just need upper triangular
789  // i0 < i1
790  int i0 = 6*(con.nd0-nFixed); // will be negative if fixed
791  int i1 = 6*(con.nd1-nFixed); // will be negative if fixed
792 
793  if (i0>=0)
794  {
795  A.block<3,3>(i0,i0) += con.w * con.J0 * con.J0.transpose();
796  }
797  if (i1>=0)
798  {
799  A.block<3,3>(i1,i1) += con.w * con.J1 * con.J1.transpose();
800  if (i0>=0)
801  {
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();
804  }
805  }
806 
807  // add in 2 blocks of B
808  if (i0>=0)
809  B.block<3,1>(i0,0) -= con.w * con.J0 * con.err;
810  if (i1>=0)
811  B.block<3,1>(i1,0) -= con.w * con.J1 * con.err;
812 
813  // scale variable, add in 5 blocks; actually just need upper triangular
814  int is = 6*nFree+con.sv;
815  A(is,is) += con.w * con.ks * con.ks;
816  if (i0>=0)
817  {
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();
820  }
821  if (i1>=0)
822  {
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();
825  }
826 
827  // add in scale block of B
828  B(is) -= con.w * (-con.ks) * con.err;
829 
830  } // finish Scale constraints
831 
832 
833  // augment diagonal
834  A.diagonal() *= lam;
835 
836  // check the matrix and vector
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; }
840 
841  for (int j=0; j<6*nFree; j++)
842  if (isnan(B[j]) ) { printf("[SetupSys] NaN in B\n"); *(int *)0x0 = 0; }
843 
844  int ndc = 0;
845  for (int i=0; i<nFree; i++)
846  if (dcnt(i) == 0) ndc++;
847 
848  if (ndc > 0)
849  cout << "[SetupSys] " << ndc << " disconnected nodes" << endl;
850  }
851 
852 
853  // Set up sparse linear system; see setupSys for algorithm.
854  // Currently doesn't work with scale variables
855  void SysSPA::setupSparseSys(double sLambda, int iter, int sparseType)
856  {
857  // set matrix sizes and clear
858  // assumes scales vars are all free
859  int nFree = nodes.size() - nFixed;
860 
861  // long long t0, t1, t2, t3;
862  // t0 = utime();
863 
864  if (iter == 0)
865  csp.setupBlockStructure(nFree); // initialize CSparse structures
866  else
867  csp.setupBlockStructure(0); // zero out CSparse structures
868 
869  // t1 = utime();
870 
871  VectorXi dcnt(nFree);
872  dcnt.setZero(nFree);
873 
874  // lambda augmentation
875  double lam = 1.0 + sLambda;
876 
877  // loop over P2 constraints
878  for(size_t pi=0; pi<p2cons.size(); pi++)
879  {
880  ConP2 &con = p2cons[pi];
881  con.setJacobians(nodes);
882 
883  // add in 4 blocks of A; actually just need upper triangular
884  int i0 = con.ndr-nFixed; // will be negative if fixed
885  int i1 = con.nd1-nFixed; // will be negative if fixed
886 
887  if (i0>=0)
888  {
889  Matrix<double,6,6> m = con.J0t*con.prec*con.J0;
890  csp.addDiagBlock(m,i0);
891  dcnt(con.ndr - nFixed)++;
892  }
893  if (i1>=0)
894  {
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);
899  if (i0>=0)
900  {
901  Matrix<double,6,6> m2 = con.J0t * tp;
902  if (i1 < i0)
903  {
904  m = m2.transpose();
905  csp.addOffdiagBlock(m,i1,i0);
906  }
907  else
908  csp.addOffdiagBlock(m2,i0,i1);
909  }
910  }
911 
912  // add in 2 blocks of B
913  if (i0>=0)
914  csp.B.block<6,1>(i0*6,0) -= con.J0t * con.prec * con.err;
915  if (i1>=0)
916  csp.B.block<6,1>(i1*6,0) -= con.J1t * con.prec * con.err;
917  } // finish P2 constraints
918 
919  // t2 = utime();
920 
921  // set up sparse matrix structure from blocks
922  if (sparseType == SBA_BLOCK_JACOBIAN_PCG)
923  csp.incDiagBlocks(lam); // increment diagonal block
924  else
925  csp.setupCSstructure(lam,iter==0);
926 
927  // t3 = utime();
928 
929  // printf("\n[SetupSparseSys] Block: %0.1f Cons: %0.1f CS: %0.1f\n",
930  // (t1-t0)*.001, (t2-t1)*.001, (t3-t2)*.001);
931 
932  int ndc = 0;
933  for (int i=0; i<nFree; i++)
934  if (dcnt(i) == 0) ndc++;
935 
936  if (ndc > 0)
937  cout << "[SetupSparseSys] " << ndc << " disconnected nodes" << endl;
938  }
939 
940 
949 
950  int SysSPA::doSPA(int niter, double sLambda, int useCSparse, double initTol,
951  int maxCGiters)
952  {
953  Node::initDr();
954  int nFree = nodes.size() - nFixed; // number of free nodes
955 
956  // number of nodes
957  int ncams = nodes.size();
958  // number of scale variables
959  int nscales = scales.size();
960 
961  // save old scales
962  vector<double> oldscales;
963  oldscales.resize(nscales);
964 
965  // initialize vars
966  if (sLambda > 0.0) // do we initialize lambda?
967  lambda = sLambda;
968 
969  // set number of constraints
970  int ncons = p2cons.size();
971 
972  // check for fixed frames
973  for (int i=0; i<ncams; i++)
974  {
975  Node &nd = nodes[i];
976  if (i >= nFixed)
977  nd.isFixed = false;
978  else
979  nd.isFixed = true;
980  nd.setTransform(); // set up world-to-node transform for cost calculation
981  nd.setDr(true); // always use local angles
982  }
983 
984  // initialize vars
985  double laminc = 2.0; // how much to increment lambda if we fail
986  double lamdec = 0.5; // how much to decrement lambda if we succeed
987  int iter = 0; // iterations
988  sqMinDelta = 1e-8 * 1e-8;
989  double cost = calcCost();
990  if (verbose)
991  cout << iter << " Initial squared cost: " << cost << " which is "
992  << sqrt(cost/ncons) << " rms error" << endl;
993 
994  int good_iter = 0;
995  for (; iter<niter; iter++) // loop at most <niter> times
996  {
997  // set up and solve linear system
998  // NOTE: shouldn't need to redo all calcs in setupSys if we
999  // got here from a bad update
1000 
1001  long long t0, t1, t2, t3;
1002  t0 = utime();
1003  if (useCSparse)
1004  setupSparseSys(lambda,iter,useCSparse); // set up sparse linear system
1005  else
1006  setupSys(lambda); // set up linear system
1007 
1008  // use appropriate linear solver
1009  if (useCSparse == SBA_BLOCK_JACOBIAN_PCG)
1010  {
1011  if (csp.B.rows() != 0)
1012  {
1013  int iters = csp.doBPCG(maxCGiters,initTol,iter);
1014  if (verbose)
1015  cout << "[Block PCG] " << iters << " iterations" << endl;
1016  }
1017  }
1018  else if (useCSparse > 0)
1019  {
1020  bool ok = csp.doChol();
1021  if (!ok)
1022  cout << "[DoSPA] Sparse Cholesky failed!" << endl;
1023  }
1024  else
1025  A.ldlt().solveInPlace(B); // Cholesky decomposition and solution
1026 
1027  // get correct result vector
1028  VectorXd &BB = useCSparse ? csp.B : B;
1029 
1030  // check for convergence
1031  // this is a pretty crummy convergence measure...
1032  double sqDiff = BB.squaredNorm();
1033  if (sqDiff < sqMinDelta) // converged, done...
1034  {
1035  break;
1036  }
1037 
1038  // update the frames
1039  int ci = 0;
1040  for(int i=0; i < ncams; i++)
1041  {
1042  Node &nd = nodes[i];
1043  if (nd.isFixed) continue; // not to be updated
1044  nd.oldtrans = nd.trans; // save in case we don't improve the cost
1045  nd.oldqrot = nd.qrot;
1046  nd.trans.head<3>() += BB.segment<3>(ci);
1047 
1048  Quaternion<double> qr;
1049  qr.vec() = BB.segment<3>(ci+3);
1050  qr.w() = sqrt(1.0 - qr.vec().squaredNorm());
1051 
1052  Quaternion<double> qrn,qrx;
1053  qrn = nd.qrot;
1054  qr = qrn*qr; // post-multiply
1055  qr.normalize();
1056  if (qr.w() < 0.0)
1057  nd.qrot.coeffs() = -qr.coeffs();
1058  else
1059  nd.qrot.coeffs() = qr.coeffs();
1060 
1061  nd.setTransform(); // set up projection matrix for cost calculation
1062  nd.setDr(true); // set rotational derivatives
1063  ci += 6; // advance B index
1064  }
1065 
1066  // update the scales
1067  ci = 6*nFree; // head of scale vars
1068  if (nscales > 0) // could be empty
1069  for(int i=0; i < nscales; i++)
1070  {
1071  oldscales[i] = scales[i];
1072  scales[i] += B(ci);
1073  ci++;
1074  }
1075 
1076 
1077  // new cost
1078  double newcost = calcCost();
1079  if (verbose)
1080  cout << iter << " Updated squared cost: " << newcost << " which is "
1081  << sqrt(newcost/ncons) << " rms error" << endl;
1082 
1083  // check if we did good
1084  if (newcost < cost) // && iter != 0) // NOTE: iter==0 case is for checking
1085  {
1086  cost = newcost;
1087  lambda *= lamdec; // decrease lambda
1088  // laminc = 2.0; // reset bad lambda factor; not sure if this is a good idea...
1089  good_iter++;
1090  }
1091  else
1092  {
1093  lambda *= laminc; // increase lambda
1094  laminc *= 2.0; // increase the increment
1095 
1096  // reset nodes
1097  for(int i=0; i<ncams; i++)
1098  {
1099  Node &nd = nodes[i];
1100  if (nd.isFixed) continue; // not to be updated
1101  nd.trans = nd.oldtrans;
1102  nd.qrot = nd.oldqrot;
1103  nd.setTransform(); // set up projection matrix for cost calculation
1104  nd.setDr(true);
1105  }
1106 
1107  // reset scales
1108  if (nscales > 0) // could be empty
1109  for(int i=0; i < nscales; i++)
1110  scales[i] = oldscales[i];
1111 
1112 
1113  cost = calcCost(); // need to reset errors
1114  if (verbose)
1115  cout << iter << " Downdated cost: " << cost << endl;
1116  // NOTE: shouldn't need to redo all calcs in setupSys
1117  }
1118  }
1119 
1120  // return number of iterations performed
1121  return good_iter;
1122 
1123  }
1124 
1125 
1126  // write out the precision matrix for CSparse
1127  void SysSPA::writeSparseA(char *fname, bool useCSparse)
1128  {
1129  ofstream ofs(fname);
1130  if (ofs == NULL)
1131  {
1132  cout << "Can't open file " << fname << endl;
1133  return;
1134  }
1135 
1136  // cameras
1137  if (useCSparse)
1138  {
1139  setupSparseSys(0.0,0,useCSparse);
1140 
1141  int *Ai = csp.A->i;
1142  int *Ap = csp.A->p;
1143  double *Ax = csp.A->x;
1144 
1145  for (int i=0; i<csp.csize; i++)
1146  for (int j=Ap[i]; j<Ap[i+1]; j++)
1147  if (Ai[j] <= i)
1148  ofs << Ai[j] << " " << i << setprecision(16) << " " << Ax[j] << endl;
1149  }
1150  else
1151  {
1152  Eigen::IOFormat pfmt(16);
1153 
1154  int nrows = A.rows();
1155  int ncols = A.cols();
1156 
1157  for (int i=0; i<nrows; i++)
1158  for (int j=i; j<ncols; j++)
1159  {
1160  double a = A(i,j);
1161  if (A(i,j) != 0.0)
1162  ofs << i << " " << j << setprecision(16) << " " << a << endl;
1163  }
1164  }
1165 
1166  ofs.close();
1167  }
1168 
1169 
1170  // Set up spanning tree initialization
1171  void SysSPA::spanningTree(int node)
1172  {
1173  int nnodes = nodes.size();
1174 
1175  // set up an index from nodes to their constraints
1176  vector<vector<int> > cind;
1177  cind.resize(nnodes);
1178 
1179  for(size_t pi=0; pi<p2cons.size(); pi++)
1180  {
1181  ConP2 &con = p2cons[pi];
1182  int i0 = con.ndr;
1183  int i1 = con.nd1;
1184  cind[i0].push_back(i1);
1185  cind[i1].push_back(i0);
1186  }
1187 
1188  // set up breadth-first algorithm
1189  VectorXd dist(nnodes);
1190  dist.setConstant(1e100);
1191  if (node >= nnodes)
1192  node = 0;
1193  dist[node] = 0.0;
1194  multimap<double,int> open; // open list, priority queue - can have duplicates
1195  open.insert(make_pair<double,int>(0.0,node));
1196 
1197  // do breadth-first computation
1198  while (!open.empty())
1199  {
1200  // get top node, remove it
1201  int ni = open.begin()->second;
1202  double di = open.begin()->first;
1203  open.erase(open.begin());
1204  if (di > dist[ni]) continue; // already dealt with
1205 
1206  // update neighbors
1207  Node &nd = nodes[ni];
1208  Matrix<double,3,4> n2w;
1209  transformF2W(n2w,nd.trans,nd.qrot); // from node to world coords
1210 
1211  vector<int> &nns = cind[ni];
1212  for (int i=0; i<(int)nns.size(); i++)
1213  {
1214  ConP2 &con = p2cons[nns[i]];
1215  double dd = con.tmean.norm(); // incremental distance
1216  // neighbor node index
1217  int nn = con.nd1;
1218  if (nn == ni)
1219  nn = con.ndr;
1220  Node &nd2 = nodes[nn];
1221  Vector3d tmean = con.tmean;
1222  Quaterniond qpmean = con.qpmean;
1223  if (nn == con.ndr) // wrong way, reverse
1224  {
1225  qpmean = qpmean.inverse();
1226  tmean = nd.qrot.toRotationMatrix().transpose()*nd2.qrot.toRotationMatrix()*tmean;
1227  }
1228 
1229  if (dist[nn] > di + dd) // is neighbor now closer?
1230  {
1231  // set priority queue
1232  dist[nn] = di+dd;
1233  open.insert(make_pair<double,int>(di+dd,nn));
1234  // update initial pose
1235  Vector4d trans;
1236  trans.head(3) = tmean;
1237  trans(3) = 1.0;
1238  nd2.trans.head(3) = n2w*trans;
1239  nd2.qrot = qpmean*nd.qrot;
1240  nd2.normRot();
1241  nd2.setTransform();
1242  nd2.setDr(true);
1243  }
1244  }
1245  }
1246 
1247  }
1248 
1249 
1250 } // namespace sba
void setDr(bool local=false)
Set angle derivates.
Definition: node.cpp:56
SysSPA holds a set of nodes and constraints for sparse pose adjustment.
Definition: sba.h:440
void normRot()
Normalize quaternion to unit. Problem with global derivatives near w=0, solved by a hack for now...
Definition: node.cpp:37
double calcErrDist(const Node &nd0, const Node &nd1)
calculate error in distance only, no weighting
Definition: spa.cpp:619
Eigen::Matrix< double, 3, 3 > dRdx
Derivatives of the rotation matrix transpose wrt quaternion xyz, used for calculating Jacobian wrt po...
Definition: node.h:126
bool readP2File(char *fname, SysSPA spa)
constraint files
Definition: spa.cpp:78
void setJacobians(std::vector< Node, Eigen::aligned_allocator< Node > > &nodes)
Definition: spa.cpp:224
Eigen::Quaternion< double > oldqrot
Previous quaternion rotation, saved for downdating within LM.
Definition: node.h:147
#define NORMALIZE_Q
Definition: spa.cpp:219
Eigen::Matrix< double, 3, 3 > dRdy
Definition: node.h:126
Eigen::Matrix< double, 6, 6 > prec
Definition: sba.h:311
Eigen::Matrix< double, 6, 6 > J1t
Definition: sba.h:324
int nd1
Node index for the second node.
Definition: sba.h:306
static long long utime()
Definition: spa.cpp:65
Eigen::Matrix< double, 6, 6 > J1
Definition: sba.h:324
bool isFixed
For SBA, is this camera fixed or free?
Definition: node.h:141
Eigen::Vector3d tmean
Mean vector, quaternion (inverse) and precision matrix for this constraint.
Definition: sba.h:309
int nd1
Node index for the second node.
Definition: sba.h:358
void transformF2W(Eigen::Matrix< double, 3, 4 > &m, const Eigen::Matrix< double, 4, 1 > &trans, const Eigen::Quaternion< double > &qrot)
Definition: node.cpp:166
Eigen::Matrix< double, 4, 1 > oldtrans
Previous translation, saved for downdating within LM.
Definition: node.h:144
double err
error
Definition: sba.h:370
double w
Weight for this constraint.
Definition: sba.h:367
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.
Definition: node.h:63
Eigen::Vector3d J0
Definition: sba.h:376
Eigen::Matrix< double, 3, 4 > w2n
Resultant transform from world to node coordinates.
Definition: node.h:80
Definition: bpcg.h:60
Eigen::Matrix< double, 6, 6 > J0
jacobian with respect to frames; uses dR&#39;/dq from Node calculation
Definition: sba.h:324
double calcErr(const Node &nd0, const Node &nd1, double alpha)
calculates projection error and stores it in <err>
Definition: spa.cpp:632
void writeSparseA(const char *fname, SysSBA &sba)
Eigen::Quaternion< double > qrot
Rotation of the node expressed as a Quaternion.
Definition: node.h:70
Eigen::Vector3d J1
Definition: sba.h:380
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Matrix< double, 4, 1 > trans
Translation in homogeneous coordinates, last element is 1.0.
Definition: node.h:69
int sv
Scale variable index.
Definition: sba.h:361
std::vector< Node, Eigen::aligned_allocator< Node > > nodes
set of nodes (camera frames) for SPA system, indexed by position;
Definition: sba.h:474
void setTransform()
Sets the transform matrices of the node.
Definition: node.cpp:8
void setJacobians(std::vector< Node, Eigen::aligned_allocator< Node > > &nodes)
jacobians are computed from (ti - tj)^2 - a*kij = 0
Definition: spa.cpp:383
Eigen::Matrix< double, 6, 1 > err
error
Definition: sba.h:315
double calcErr(const Node &nd0, const Node &nd1)
calculates projection error and stores it in <err>
Definition: spa.cpp:589
Eigen::Matrix< double, 3, 3 > dRdz
Definition: node.h:126
Eigen::Matrix< double, 6, 6 > J0t
Definition: sba.h:324
#define SBA_BLOCK_JACOBIAN_PCG
Definition: sba.h:69
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int nd0
Reference pose index.
Definition: sba.h:355
Eigen::Quaternion< double > qpmean
Definition: sba.h:310
std::vector< ConP2, Eigen::aligned_allocator< ConP2 > > p2cons
Set of P2 constraints.
Definition: sba.h:483
double ks
Scale factor for this constraint.
Definition: sba.h:364
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int ndr
Reference pose index.
Definition: sba.h:303
std::vector< ConScale, Eigen::aligned_allocator< ConScale > > scons
Set of scale constraints.
Definition: sba.h:486


sparse_bundle_adjustment
Author(s):
autogenerated on Fri Apr 3 2020 03:30:53