00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
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);
00063 return (0) ;
00064 }
00065 n = A->n ;
00066 N = cs_chol_workspace (A, S, work, x) ;
00067 if (!N) {
00068 fprintf(stderr, "%s: cholesky failed!\n", __PRETTY_FUNCTION__);
00069
00070 }
00071 ok = (N != NULL) ;
00072 if (ok)
00073 {
00074 cs_ipvec (S->pinv, b, x, n) ;
00075 cs_lsolve (N->L, x) ;
00076 cs_ltsolve (N->L, x) ;
00077 cs_pvec (S->pinv, x, b, n) ;
00078 }
00079 cs_nfree (N) ;
00080 return (ok) ;
00081 }
00082
00087
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)) ;
00097 c = cin ;
00098 x = xin ;
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 ;
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) ;
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++)
00110 {
00111
00112 top = cs_ereach (C, k, parent, s, c) ;
00113 x [k] = 0 ;
00114 for (p = Cp [k] ; p < Cp [k+1] ; p++)
00115 {
00116 if (Ci [p] <= k) x [Ci [p]] = Cx [p] ;
00117 }
00118 d = x [k] ;
00119 x [k] = 0 ;
00120
00121 for ( ; top < n ; top++)
00122 {
00123 i = s [top] ;
00124 lki = x [i] / Lx [Lp [i]] ;
00125 x [i] = 0 ;
00126 for (p = Lp [i] + 1 ; p < c [i] ; p++)
00127 {
00128 x [Li [p]] -= Lx [p] * lki ;
00129 }
00130 d -= lki * lki ;
00131 p = c [i]++ ;
00132 Li [p] = k ;
00133 Lx [p] = lki ;
00134 }
00135
00136 if (d <= 0) return (cs_ndone (N, E, NULL, NULL, 0)) ;
00137 p = c [k]++ ;
00138 Li [p] = k ;
00139 Lx [p] = sqrt (d) ;
00140 }
00141 Lp [n] = cp [n] ;
00142 return (cs_ndone (N, E, NULL, NULL, 1)) ;
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) {
00151 return writeCCSMatrix(filename, rows, cols, A->p, A->i, A->x, upperTriangular);
00152 }
00153
00154
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;
00163 int *Ai = A->i;
00164 double *Ax = A->x;
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
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 }