csparse_helper.cpp
Go to the documentation of this file.
00001 // g2o - General Graph Optimization
00002 // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
00003 // 
00004 // g2o is free software: you can redistribute it and/or modify
00005 // it under the terms of the GNU Lesser General Public License as published
00006 // by the Free Software Foundation, either version 3 of the License, or
00007 // (at your option) any later version.
00008 // 
00009 // g2o is distributed in the hope that it will be useful,
00010 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00011 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00012 // GNU Lesser General Public License for more details.
00013 // 
00014 // You should have received a copy of the GNU Lesser General Public License
00015 // along with this program.  If not, see <http://www.gnu.org/licenses/>.
00016 
00017 #include "csparse_helper.h"
00018 
00019 #include "g2o/stuff/sparse_helper.h"
00020 #include "g2o/stuff/macros.h"
00021 
00022 #include <string>
00023 #include <cassert>
00024 #include <fstream>
00025 #include <cstring>
00026 #include <iomanip>
00027 #include <iostream>
00028 #include <algorithm>
00029 #include <vector>
00030 
00031 using namespace std;
00032 
00033 namespace g2o {
00034 
00035   struct SparseMatrixEntry{
00036     SparseMatrixEntry(int r=-1, int c=-1, double x=0.) :
00037       _r(r), _c(c), _x(x)
00038     {
00039     }
00040     int _r,_c;
00041     double _x;
00042   };
00043 
00044   struct SparseMatrixEntryColSort
00045   {
00046     bool operator()(const SparseMatrixEntry& e1, const SparseMatrixEntry& e2) const
00047     {
00048       return e1._c < e2._c || (e1._c == e2._c && e1._r < e2._r);
00049     }
00050   };
00051 
00056   int cs_cholsolsymb(const cs *A, double *b, const css* S, double* x, int* work)
00057   {
00058     csn *N ;
00059     int n, ok ;
00060     if (!CS_CSC (A) || !b || ! S || !x) {
00061       fprintf(stderr, "%s: No valid input!\n", __PRETTY_FUNCTION__);
00062       assert(0); // get a backtrace in debug mode
00063       return (0) ;     /* check inputs */
00064     }
00065     n = A->n ;
00066     N = cs_chol_workspace (A, S, work, x) ;                    /* numeric Cholesky factorization */
00067     if (!N) {
00068       fprintf(stderr, "%s: cholesky failed!\n", __PRETTY_FUNCTION__);
00069       /*assert(0);*/
00070     }
00071     ok = (N != NULL) ;
00072     if (ok)
00073     {
00074       cs_ipvec (S->pinv, b, x, n) ;   /* x = P*b */
00075       cs_lsolve (N->L, x) ;           /* x = L\x */
00076       cs_ltsolve (N->L, x) ;          /* x = L'\x */
00077       cs_pvec (S->pinv, x, b, n) ;    /* b = P'*x */
00078     }
00079     cs_nfree (N) ;
00080     return (ok) ;
00081   }
00082 
00087   /* L = chol (A, [pinv parent cp]), pinv is optional */
00088   csn* cs_chol_workspace (const cs *A, const css *S, int* cin, double* xin)
00089   {
00090     double d, lki, *Lx, *x, *Cx ;
00091     int top, i, p, k, n, *Li, *Lp, *cp, *pinv, *s, *c, *parent, *Cp, *Ci ;
00092     cs *L, *C, *E ;
00093     csn *N ;
00094     if (!CS_CSC (A) || !S || !S->cp || !S->parent) return (NULL) ;
00095     n = A->n ;
00096     N = (csn*) cs_calloc (1, sizeof (csn)) ;       /* allocate result */
00097     c = cin ;     /* get int workspace */
00098     x = xin ;    /* get double workspace */
00099     cp = S->cp ; pinv = S->pinv ; parent = S->parent ;
00100     C = pinv ? cs_symperm (A, pinv, 1) : ((cs *) A) ;
00101     E = pinv ? C : NULL ;           /* E is alias for A, or a copy E=A(p,p) */
00102     if (!N || !c || !x || !C) return (cs_ndone (N, E, NULL, NULL, 0)) ;
00103     s = c + n ;
00104     Cp = C->p ; Ci = C->i ; Cx = C->x ;
00105     N->L = L = cs_spalloc (n, n, cp [n], 1, 0) ;    /* allocate result */
00106     if (!L) return (cs_ndone (N, E, NULL, NULL, 0)) ;
00107     Lp = L->p ; Li = L->i ; Lx = L->x ;
00108     for (k = 0 ; k < n ; k++) Lp [k] = c [k] = cp [k] ;
00109     for (k = 0 ; k < n ; k++)       /* compute L(k,:) for L*L' = C */
00110     {
00111       /* --- Nonzero pattern of L(k,:) ------------------------------------ */
00112       top = cs_ereach (C, k, parent, s, c) ;      /* find pattern of L(k,:) */
00113       x [k] = 0 ;                                 /* x (0:k) is now zero */
00114       for (p = Cp [k] ; p < Cp [k+1] ; p++)       /* x = full(triu(C(:,k))) */
00115       {
00116         if (Ci [p] <= k) x [Ci [p]] = Cx [p] ;
00117       }
00118       d = x [k] ;                     /* d = C(k,k) */
00119       x [k] = 0 ;                     /* clear x for k+1st iteration */
00120       /* --- Triangular solve --------------------------------------------- */
00121       for ( ; top < n ; top++)    /* solve L(0:k-1,0:k-1) * x = C(:,k) */
00122       {
00123         i = s [top] ;               /* s [top..n-1] is pattern of L(k,:) */
00124         lki = x [i] / Lx [Lp [i]] ; /* L(k,i) = x (i) / L(i,i) */
00125         x [i] = 0 ;                 /* clear x for k+1st iteration */
00126         for (p = Lp [i] + 1 ; p < c [i] ; p++)
00127         {
00128           x [Li [p]] -= Lx [p] * lki ;
00129         }
00130         d -= lki * lki ;            /* d = d - L(k,i)*L(k,i) */
00131         p = c [i]++ ;
00132         Li [p] = k ;                /* store L(k,i) in column i */
00133         Lx [p] = lki ;
00134       }
00135       /* --- Compute L(k,k) ----------------------------------------------- */
00136       if (d <= 0) return (cs_ndone (N, E, NULL, NULL, 0)) ; /* not pos def */
00137       p = c [k]++ ;
00138       Li [p] = k ;                /* store L(k,k) = sqrt (d) in column k */
00139       Lx [p] = sqrt (d) ;
00140     }
00141     Lp [n] = cp [n] ;               /* finalize L */
00142     return (cs_ndone (N, E, NULL, NULL, 1)) ; /* success: free E,s,x; return N */
00143   }
00144 
00145   bool writeCs2Octave(const char* filename, const cs* A, bool upperTriangular)
00146   {
00147     int cols = A->n;
00148     int rows = A->m;
00149 
00150     if (A->nz == -1) { // CCS matrix
00151       return writeCCSMatrix(filename, rows, cols, A->p, A->i, A->x, upperTriangular);
00152     }
00153 
00154     // Triplet matrix
00155     string name = filename;
00156     std::string::size_type lastDot = name.find_last_of('.');
00157     if (lastDot != std::string::npos) 
00158       name = name.substr(0, lastDot);
00159 
00160     vector<SparseMatrixEntry> entries;
00161     entries.reserve(A->nz);
00162     int *Aj = A->p;             // column indeces
00163     int *Ai = A->i;             // row indices
00164     double *Ax = A->x;          // values;
00165     for (int i = 0; i < A->nz; ++i) {
00166       entries.push_back(SparseMatrixEntry(Ai[i], Aj[i], Ax[i]));
00167       if (upperTriangular && Ai[i] != Aj[i])
00168         entries.push_back(SparseMatrixEntry(Aj[i], Ai[i], Ax[i]));
00169     }
00170     sort(entries.begin(), entries.end(), SparseMatrixEntryColSort());
00171 
00172     std::ofstream fout(filename);
00173     fout << "# name: " << name << std::endl;
00174     fout << "# type: sparse matrix" << std::endl;
00175     fout << "# nnz: " << entries.size() << std::endl;
00176     fout << "# rows: " << rows << std::endl;
00177     fout << "# columns: " << cols << std::endl;
00178     //fout << fixed;
00179     fout << setprecision(9) << endl;
00180 
00181     for (vector<SparseMatrixEntry>::const_iterator it = entries.begin(); it != entries.end(); ++it) {
00182       const SparseMatrixEntry& entry = *it;
00183       fout << entry._r+1 << " " << entry._c+1 << " " << entry._x << std::endl;
00184     }
00185     return fout.good();
00186   }
00187 
00188 } // end namespace


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:31:00