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