csparse.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 // Interface to CSparse
37 //
38 
39 #include <stdio.h>
41 
42 using namespace Eigen;
43 
44 #include <iostream>
45 #include <iomanip>
46 #include <fstream>
47 #include <sys/time.h>
48 #include <algorithm>
49 
50 using namespace std;
51 
52 
53 //
54 // Efficient interface to the CSparse sparse solver
55 //
56 // Basic idea is to store 6x6 blocks in a sparse structure,
57 // and when we're done forming the A matrix, transfer to
58 // a CSparse compressed structure. The latter only has
59 // to be initialized once at the start of the nonlinear iterations.
60 //
61 
62 //
63 // CSparse holds its sparse NxN arrays in compressed column format:
64 //
65 // col_ptr has N+1 entries, one for each column, and a final NNZ entry.
66 // each entry is the index in row_ptr of where the column starts.
67 // row_ind has NNZ entries, each one a row index for an element.
68 // vals has NNZ entries corresponding to the row_ptr entries
69 //
70 
71 namespace sba
72 {
73 
74  CSparse::CSparse()
75  {
76  A = NULL;
77 #ifdef SBA_CHOLMOD
78  chA = NULL;
79  chInited = false;
80 #endif
81  useCholmod = false;
82  asize = 0;
83  csize = 0;
84  nnz = 0;
85  }
86 
87  CSparse::~CSparse()
88  {
89  if (A) cs_spfree(A); // free any previous structure
90  }
91 
92 
93  // 6x6 sparse jacobian blocks
94  void CSparse::setupBlockStructure(int n)
95  {
96  if (n > 0) // set up initial structure
97  {
98  diag.clear();
99  diag.resize(n);
100  cols.clear();
101  cols.resize(n);
102  asize = n;
103  csize = 6*n;
104  }
105 
106  // zero out entries
107  B.setZero(csize);
108  for (int i=0; i<(int)diag.size(); i++)
109  diag[i].setZero();
110  for (int i=0; i<(int)cols.size(); i++)
111  {
112  map<int,Matrix<double,6,6>, less<int>,
113  aligned_allocator<Matrix<double,6,6> > > &col = cols[i];
114  if (col.size() > 0)
115  {
116  map<int,Matrix<double,6,6>, less<int>,
117  aligned_allocator<Matrix<double,6,6> > >::iterator it;
118  for (it = col.begin(); it != col.end(); it++)
119  it->second.setZero();
120  }
121  }
122  }
123 
124  void CSparse::incDiagBlocks(double lam)
125  {
126  for (int i=0; i<(int)diag.size(); i++)
127  diag[i].diagonal() *= lam;
128  }
129 
130  // add an off-diagonal block
131  void CSparse::addOffdiagBlock(Matrix<double,6,6> &m, int ii, int jj)
132  {
133  // get column
134  map<int,Matrix<double,6,6>, less<int>,
135  aligned_allocator<Matrix<double,6,6> > > &col = cols[jj];
136  // find current matrix
137  map<int,Matrix<double,6,6>, less<int>,
138  aligned_allocator<Matrix<double,6,6> > >::iterator it;
139  it = col.find(ii);
140  if (it == col.end()) // didn't find it
141  col.insert(pair<int,Matrix<double,6,6> >(ii,m));
142  else // found it, add
143  it->second += m;
144  }
145 
146 
147  // set up CSparse structure; <init> true if first time
148  // <diaginc> is the diagonal multiplier for LM
149 
150  // this version sets upper triangular matrix,
151  void CSparse::setupCSstructure(double diaginc, bool init)
152  {
153 #ifdef SBA_CHOLMOD
154  if (useCholmod) {
155  cholmod_start(&Common); // this is finished in doChol()
156  Common.print = 0;
157  }
158 #endif
159 
160  // reserve space and set things up
161  if (init || useCholmod)
162  {
163  // count entries for cs allocation
164  nnz = 21*asize; // diagonal entries, just upper triangle
165  for (int i=0; i<(int)cols.size(); i++)
166  {
167  map<int,Matrix<double,6,6>, less<int>,
168  aligned_allocator<Matrix<double,6,6> > > &col = cols[i];
169  nnz += 36 * col.size(); // 6x6 matrix
170  }
171 
172 #ifdef SBA_CHOLMOD
173  if (useCholmod)
174  {
175  // cholmod_start(&Common); // this is finished in doChol()
176  // if (chA)
177  // cholmod_free_sparse(&chA, &Common);
178  chA = cholmod_allocate_sparse(csize,csize,nnz,true,true,1,CHOLMOD_REAL,&Common);
179  }
180  else
181 #endif
182  {
183  if (A) cs_spfree(A); // free any previous structure
184  A = cs_spalloc(csize,csize,nnz,1,0); // allocate sparse matrix
185  }
186 
187  // now figure out the column pointers
188  int colp = 0; // index of where the column starts in Ai
189  int *Ap, *Ai;
190 #ifdef SBA_CHOLMOD
191  if (useCholmod)
192  {
193  Ap = (int *)chA->p; // column pointer
194  Ai = (int *)chA->i; // row indices
195  }
196  else
197 #endif
198  {
199  Ap = A->p; // column pointer
200  Ai = A->i; // row indices
201  }
202  for (int i=0; i<(int)cols.size(); i++)
203  {
204  // column i entries
205  map<int,Matrix<double,6,6>, less<int>,
206  aligned_allocator<Matrix<double,6,6> > > &col = cols[i];
207 
208  // do this for 6 columns
209  for (int k=0; k<6; k++)
210  {
211  *Ap++ = colp;
212  int row;
213 
214  // iterate over the map
215  if (col.size() > 0)
216  {
217  // map iterator
218  map<int,Matrix<double,6,6>, less<int>,
219  aligned_allocator<Matrix<double,6,6> > >::iterator it;
220 
221  // iterate over block column entries
222  for (it = col.begin(); it != col.end(); it++)
223  {
224  row = 6*it->first; // which row we're at
225  for (int j=0; j<6; j++)
226  Ai[colp++] = row++;
227  }
228  }
229 
230  // add in diagonal entries
231  row = 6*i;
232  for (int kk=0; kk<k+1; kk++)
233  Ai[colp++] = row++;
234  }
235  }
236  *Ap = nnz; // last entry
237  }
238 
239 
240 
241  // now put the entries in place
242  int colp = 0; // index of where the column starts in Ai
243  double *Ax;
244 #ifdef SBA_CHOLMOD
245  if (useCholmod)
246  Ax = (double *)chA->x; // values
247  else
248 #endif
249  Ax = A->x; // values
250  for (int i=0; i<(int)cols.size(); i++)
251  {
252  // column i entries
253  map<int,Matrix<double,6,6>, less<int>,
254  aligned_allocator<Matrix<double,6,6> > > &col = cols[i];
255 
256  // do this for 6 columns
257  for (int k=0; k<6; k++)
258  {
259  // iterate over the map
260  if (col.size() > 0)
261  {
262  // map iterator
263  map<int,Matrix<double,6,6>, less<int>,
264  aligned_allocator<Matrix<double,6,6> > >::iterator it;
265 
266  // iterate over block column entries
267  for (it = col.begin(); it != col.end(); it++)
268  {
269  Matrix<double,6,6> &m = it->second;
270  for (int j=0; j<6; j++)
271  Ax[colp++] = m(j,k);
272  }
273  }
274 
275  // add in diagonal entries
276  Matrix<double,6,6> &m = diag[i]; // diagonal block
277  for (int kk=0; kk<k+1; kk++)
278  Ax[colp++] = m(kk,k);
279  Ax[colp-1] *= diaginc; // increment diagonal for LM
280  }
281  }
282 
283  }
284 
285 
286  // uncompress the compressed A into a dense Eigen matrix
287  void CSparse::uncompress(MatrixXd &m)
288  {
289  if (!A) return;
290  m.setZero(csize,csize);
291 
292  int *Ap = A->p; // column pointer
293  int *Ai = A->i; // row indices
294  double *Ax = A->x; // values;
295 
296  for (int i=0; i<csize; i++)
297  {
298  int rbeg = Ap[i];
299  int rend = Ap[i+1];
300  if (rend > rbeg)
301  for (int j=rbeg; j<rend; j++)
302  m(Ai[j],i) = Ax[j];
303  }
304  }
305 
306  // solve in place, returns RHS B
307  bool CSparse::doChol()
308  {
309 #ifdef SBA_CHOLMOD
310  if (useCholmod)
311  {
312  cholmod_dense *x, b, *R, *R2;
313  cholmod_factor *L ;
314  double *Xx, *Rx, *bb;
315  double one [2], minusone [2];
316  one [0] = 1 ;
317  one [1] = 0 ;
318  minusone [0] = -1 ;
319  minusone [1] = 0 ;
320 
321  // cholmod_start (&Common) ; // start it up ???
322  cholmod_print_sparse (chA, (char *)"A", &Common) ; // print simple stats
323  b.nrow = csize;
324  b.ncol = 1;
325  b.d = csize; // leading dimension (???)
326  b.nzmax = csize;
327  b.xtype = CHOLMOD_REAL;
328  b.dtype = CHOLMOD_DOUBLE;
329  b.x = B.data();
330  //cout << "CHOLMOD analyze..." << flush;
331  L = cholmod_analyze (chA, &Common) ; // analyze
332  //cout << "factorize..." << flush;
333  cholmod_factorize (chA, L, &Common) ; // factorize
334  //cout << "solve..." << flush;
335  x = cholmod_solve (CHOLMOD_A, L, &b, &Common) ; // solve Ax=b
336  // cholmod_print_factor (L, (char *)"L", &Common) ;
337 
338  //cout << "refine" << endl;
339  // one step of iterative refinement, cheap
340  /* Ax=b was factorized and solved, R = B-A*X */
341  R = cholmod_copy_dense (&b, &Common) ;
342  cholmod_sdmult(chA, 0, minusone, one, x, R, &Common) ;
343  /* R2 = A\(B-A*X) */
344  R2 = cholmod_solve (CHOLMOD_A, L, R, &Common) ;
345  /* compute X = X + A\(B-A*X) */
346  Xx = (double *)x->x ;
347  Rx = (double *)R2->x ;
348  for (int i=0 ; i<csize ; i++)
349  {
350  Xx[i] = Xx[i] + Rx[i] ;
351  }
352  cholmod_free_dense (&R2, &Common) ;
353  cholmod_free_dense (&R, &Common) ;
354 
355  bb = B.data();
356  for (int i=0; i<csize; i++) // transfer answer
357  *bb++ = *Xx++;
358  cholmod_free_factor (&L, &Common) ; // free matrices
359  cholmod_free_dense (&x, &Common) ;
360  cholmod_free_sparse(&chA, &Common);
361  cholmod_finish (&Common) ; // finish it ???
362 
363  return true;
364  }
365  else
366 #endif
367  {
368  // using order 0 here (natural order);
369  // may be better to use "1" for large problems
370  int order = 0;
371  if (csize > 400) order = 1;
372  bool ok = (bool)cs_cholsol(order,A,B.data()); // do the CSparse thang
373  return ok;
374  }
375  }
376 
377 
378  //
379  // block jacobian PCG
380  // max iterations <iter>, ending toleranace <tol>
381  //
382 
383  int
384  CSparse::doBPCG(int iters, double tol, int sba_iter)
385  {
386  int n = B.rows();
387  VectorXd x;
388  x.setZero(n);
389  bool abstol = false;
390  if (sba_iter > 0) abstol = true;
391  int ret;
392  ret = bpcg.doBPCG2(iters, tol, diag, cols, x, B, abstol);
393  B = x; // transfer result data
394  return ret;
395  }
396 
397 
398  //
399  // 2d version
400  //
401 
402  CSparse2d::CSparse2d()
403  {
404  A = NULL;
405  AF = NULL;
406 #ifdef SBA_CHOLMOD
407  chA = NULL;
408  chInited = false;
409  Common.print=0;
410 #endif
411  useCholmod = false;
412  asize = 0;
413  csize = 0;
414  nnz = 0;
415  Bprev.resize(0);
416  }
417 
418  CSparse2d::~CSparse2d()
419  {
420  if (A) cs_spfree(A); // free any previous structure
421  if (AF) cs_spfree(AF); // free any previous structure
422  }
423 
424 
425  // 3x3 sparse jacobian blocks
426  void CSparse2d::setupBlockStructure(int n, bool eraseit)
427  {
428  if (n > 0) // set up initial structure
429  {
430  diag.resize(n);
431  cols.resize(n);
432  if (eraseit)
433  for (int i=0; i<(int)cols.size(); i++)
434  {
435  map<int,Matrix<double,3,3>, less<int>,
436  aligned_allocator< Matrix <double,3,3> > > &col = cols[i];
437  col.clear();
438  }
439  asize = n;
440  csize = 3*n;
441  }
442 
443  if (eraseit)
444  {
445  // zero out entries
446  B.setZero(csize);
447  for (int i=0; i<(int)diag.size(); i++)
448  diag[i].setZero();
449  for (int i=0; i<(int)cols.size(); i++)
450  {
451  map<int,Matrix<double,3,3>, less<int>,
452  aligned_allocator<Matrix<double,3,3> > > &col = cols[i];
453  if (col.size() > 0)
454  {
455  map<int,Matrix<double,3,3>, less<int>,
456  aligned_allocator<Matrix<double,3,3> > >::iterator it;
457  for (it = col.begin(); it != col.end(); it++)
458  it->second.setZero();
459  }
460  }
461  }
462 
463  else // here we just resize B, saving the old parts
464  {
465  B.setZero(csize);
466  if (Bprev.size() > 0)
467  B.head(Bprev.size()) = Bprev;
468  }
469  }
470 
471 
472  // add an off-diagonal block
473  void CSparse2d::addOffdiagBlock(Matrix<double,3,3> &m, int ii, int jj)
474  {
475  // get column
476  map<int,Matrix<double,3,3>, less<int>,
477  aligned_allocator<Matrix<double,3,3> > > &col = cols[jj];
478  // find current matrix
479  map<int,Matrix<double,3,3>, less<int>,
480  aligned_allocator<Matrix<double,3,3> > >::iterator it;
481  it = col.find(ii);
482  if (it == col.end()) // didn't find it
483  col.insert(pair<int,Matrix<double,3,3> >(ii,m));
484  else // found it, add
485  it->second += m;
486  }
487 
488 
489  void CSparse2d::incDiagBlocks(double lam)
490  {
491  for (int i=0; i<(int)diag.size(); i++)
492  diag[i].diagonal() *= lam;
493  }
494 
495 
496  // set up CSparse2d structure; <init> true if first time
497  // <diaginc> is the diagonal multiplier for LM
498 
499  // this version only sets upper triangular matrix,
500  // should set whole thing
501 
502  void CSparse2d::setupCSstructure(double diaginc, bool init)
503  {
504 #ifdef SBA_CHOLMOD
505  if (useCholmod) {
506  cholmod_start(&Common); // this is finished in doChol()
507  Common.print = 0;
508  }
509 #endif
510 
511  // reserve space and set things up
512  if (init || useCholmod)
513  {
514  if (A) cs_spfree(A); // free any previous structure
515 
516  // count entries for cs allocation
517  nnz = 6*asize; // diagonal entries, just upper triangle
518  for (int i=0; i<(int)cols.size(); i++)
519  {
520  map<int,Matrix<double,3,3>, less<int>,
521  aligned_allocator<Matrix<double,3,3> > > &col = cols[i];
522  nnz += 9 * col.size(); // 3x3 matrix
523  }
524 #ifdef SBA_CHOLMOD
525  if (useCholmod)
526  {
527  // cholmod_start(&Common); // this is finished in doChol()
528  // if (chA)
529  // cholmod_free_sparse(&chA, &Common);
530  chA = cholmod_allocate_sparse(csize,csize,nnz,true,true,1,CHOLMOD_REAL,&Common);
531  }
532  else
533 #endif
534  {
535  A = cs_spalloc(csize,csize,nnz,1,0); // allocate sparse matrix
536  }
537 
538  // now figure out the column pointers
539  int colp = 0; // index of where the column starts in Ai
540  int *Ap, *Ai;
541 #ifdef SBA_CHOLMOD
542  if (useCholmod)
543  {
544  Ap = (int *)chA->p; // column pointer
545  Ai = (int *)chA->i; // row indices
546  }
547  else
548 #endif
549  {
550  Ap = A->p; // column pointer
551  Ai = A->i; // row indices
552  }
553 
554  for (int i=0; i<(int)cols.size(); i++)
555  {
556  // column i entries
557  map<int,Matrix<double,3,3>, less<int>,
558  aligned_allocator<Matrix<double,3,3> > > &col = cols[i];
559 
560  // do this for 3 columns
561  for (int k=0; k<3; k++)
562  {
563  *Ap++ = colp;
564  int row;
565 
566  // iterate over the map
567  if (col.size() > 0)
568  {
569  // map iterator
570  map<int,Matrix<double,3,3>, less<int>,
571  aligned_allocator<Matrix<double,3,3> > >::iterator it;
572 
573  // iterate over block column entries
574  for (it = col.begin(); it != col.end(); it++)
575  {
576  row = 3*it->first; // which row we're at
577  for (int j=0; j<3; j++)
578  Ai[colp++] = row++;
579  }
580  }
581 
582  // add in diagonal entries
583  row = 3*i;
584  for (int kk=0; kk<k+1; kk++)
585  Ai[colp++] = row++;
586  }
587  }
588  *Ap = nnz; // last entry
589  }
590 
591  // now put the entries in place
592  int colp = 0; // index of where the column starts in Ai
593  double *Ax;
594 #ifdef SBA_CHOLMOD
595  if (useCholmod)
596  Ax = (double *)chA->x; // values
597  else
598 #endif
599  Ax = A->x; // values
600 
601  for (int i=0; i<(int)cols.size(); i++)
602  {
603  // column i entries
604  map<int,Matrix<double,3,3>, less<int>,
605  aligned_allocator<Matrix<double,3,3> > > &col = cols[i];
606 
607  // do this for 3 columns
608  for (int k=0; k<3; k++)
609  {
610  // iterate over the map
611  if (col.size() > 0)
612  {
613  // map iterator
614  map<int,Matrix<double,3,3>, less<int>,
615  aligned_allocator<Matrix<double,3,3> > >::iterator it;
616 
617  // iterate over block column entries
618  for (it = col.begin(); it != col.end(); it++)
619  {
620  Matrix<double,3,3> &m = it->second;
621  for (int j=0; j<3; j++)
622  Ax[colp++] = m(j,k);
623  }
624  }
625 
626  // add in diagonal entries
627  Matrix<double,3,3> &m = diag[i]; // diagonal block
628  for (int kk=0; kk<k+1; kk++)
629  Ax[colp++] = m(kk,k);
630  Ax[colp-1] *= diaginc; // increment diagonal for LM
631  }
632  }
633 
634  // make symmetric from upper diagonal
635  // this could be more efficient if AT were eliminated and AF were fixed
636  // oops - chol_sol only needs upper diag
637  }
638 
639 
640  // uncompress the compressed A into a dense Eigen matrix
641  void CSparse2d::uncompress(MatrixXd &m)
642  {
643  if (!A) return;
644  m.setZero(csize,csize);
645 
646  int *Ap = A->p; // column pointer
647  int *Ai = A->i; // row indices
648  double *Ax = A->x; // values;
649 
650  for (int i=0; i<csize; i++)
651  {
652  int rbeg = Ap[i];
653  int rend = Ap[i+1];
654  if (rend > rbeg)
655  for (int j=rbeg; j<rend; j++)
656  m(Ai[j],i) = Ax[j];
657  }
658  }
659 
660  // solve in place, returns RHS B
661  bool CSparse2d::doChol()
662  {
663 #ifdef SBA_CHOLMOD
664  if (useCholmod)
665  {
666  cholmod_dense *x, b, *R, *R2;
667  cholmod_factor *L ;
668  double *Xx, *Rx, *bb;
669  double one [2], minusone [2];
670  one [0] = 1 ;
671  one [1] = 0 ;
672  minusone [0] = -1 ;
673  minusone [1] = 0 ;
674 
675  // cholmod_start (&Common) ; // start it up ???
676  cholmod_print_sparse (chA, (char *)"A", &Common) ; // print simple stats
677  b.nrow = csize;
678  b.ncol = 1;
679  b.d = csize; // leading dimension (???)
680  b.nzmax = csize;
681  b.xtype = CHOLMOD_REAL;
682  b.dtype = CHOLMOD_DOUBLE;
683  b.x = B.data();
684  //cout << "CHOLMOD analyze..." << flush;
685  L = cholmod_analyze (chA, &Common) ; // analyze
686  //cout << "factorize..." << flush;
687  cholmod_factorize (chA, L, &Common) ; // factorize
688  //cout << "solve..." << flush;
689  x = cholmod_solve (CHOLMOD_A, L, &b, &Common) ; // solve Ax=b
690  // cholmod_print_factor (L, (char *)"L", &Common) ;
691 
692  //cout << "refine" << endl;
693  // one step of iterative refinement, cheap
694  /* Ax=b was factorized and solved, R = B-A*X */
695  R = cholmod_copy_dense (&b, &Common) ;
696  cholmod_sdmult(chA, 0, minusone, one, x, R, &Common) ;
697  /* R2 = A\(B-A*X) */
698  R2 = cholmod_solve (CHOLMOD_A, L, R, &Common) ;
699  /* compute X = X + A\(B-A*X) */
700  Xx = (double *)x->x ;
701  Rx = (double *)R2->x ;
702  for (int i=0 ; i<csize ; i++)
703  {
704  Xx[i] = Xx[i] + Rx[i] ;
705  }
706  cholmod_free_dense (&R2, &Common) ;
707  cholmod_free_dense (&R, &Common) ;
708 
709  bb = B.data();
710  for (int i=0; i<csize; i++) // transfer answer
711  *bb++ = *Xx++;
712  cholmod_free_factor (&L, &Common) ; // free matrices
713  cholmod_free_dense (&x, &Common) ;
714  cholmod_free_sparse(&chA, &Common);
715  cholmod_finish (&Common) ; // finish it ???
716 
717  return true;
718  }
719  else
720 #endif
721  {
722 
723  // using order 0 here (natural order);
724  // may be better to use "1" for large problems (AMD)
725  int order = 0;
726  if (csize > 100) order = 1;
727  bool ok = (bool)cs_cholsol(order,A,B.data()); // do the CSparse2d thang
728  return ok;
729  }
730  }
731 
732 
733  //
734  // block jacobian PCG
735  // max iterations <iter>, ending toleranace <tol>
736  //
737 
738  int
739  CSparse2d::doBPCG(int iters, double tol, int sba_iter)
740  {
741  int n = B.rows();
742  VectorXd x;
743  x.setZero(n);
744  bool abstol = false;
745  if (sba_iter > 0) abstol = true;
746  int ret;
747  ret = bpcg.doBPCG2(iters, tol, diag, cols, x, B, abstol);
748  B = x; // transfer result data
749  return ret;
750  }
751 
752 
753 #ifdef SBA_DSIF
754  // solve in place, returns RHS B
755  // PCG algorithm from SparseLib++, IML++
756  int CSparse2d::doPCG(int iters)
757  {
758  // first convert sparse matrix to SparseLib++ format
759  // do we need just upper triangular here???
760 
761  // add in lower triangular part
762  cs *AT;
763  AT = cs_transpose(A,1);
764  cs_fkeep (AT, &dropdiag, NULL); // drop diagonal entries from AT
765  if (AF) cs_spfree(AF); // free any previous structure
766  AF = cs_add (A, AT, 1, 1); // AF = A+AT
767  cs_spfree (AT);
768 
769  // convert to SparseLib objects
770  CompCol_Mat_double Ap(csize, csize, AF->nzmax, AF->x, AF->i, AF->p);
771  VECTOR_double b(B.data(),csize); // Create rhs
772  VECTOR_double x(csize, 0.0); // solution vectors
773 
774  // perform PCG
775  int res;
776  double tol = 1e-6;
777  ICPreconditioner_double D(Ap); // Create diagonal preconditioner
778  res = CG(Ap,x,b,D,iters,tol); // Solve system
779 
780  for (int i=0; i<csize; i++)
781  B[i] = x[i];
782 
783  // cout << "CG flag = " << res << endl;
784  // cout << "iterations performed: " << iters << endl;
785  // cout << "tolerance achieved : " << tol << endl;
786  // cout << x << endl;
787 
788  return res;
789  }
790 #endif
791 
792 
793 } // end namespace sba
Definition: bpcg.h:60


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