00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef LINEAR_SOLVER_CHOLMOD_ONLINE
00018 #define LINEAR_SOLVER_CHOLMOD_ONLINE
00019
00020 #include <camd.h>
00021
00022 #include "g2o/solvers/cholmod/linear_solver_cholmod.h"
00023
00024 namespace g2o {
00025
00029 class LinearSolverCholmodOnlineInterface
00030 {
00031 public:
00032 LinearSolverCholmodOnlineInterface() : cmember(0), batchEveryN(100) {}
00033 virtual int choleskyUpdate(cholmod_sparse* update) = 0;
00034 virtual bool solve(double* x, double* b) = 0;
00035 virtual cholmod_factor* L() const = 0;
00036 VectorXi* cmember;
00037 int batchEveryN;
00038 };
00039
00043 template <typename MatrixType>
00044 class LinearSolverCholmodOnline : public LinearSolver<MatrixType>, public LinearSolverCholmodOnlineInterface
00045 {
00046 public:
00047 LinearSolverCholmodOnline() :
00048 LinearSolver<MatrixType>()
00049 {
00050 _cholmodSparse = new CholmodExt();
00051 _cholmodFactor = 0;
00052 cholmod_start(&_cholmodCommon);
00053
00054
00055 _cholmodCommon.nmethods = 1 ;
00056 _cholmodCommon.method[0].ordering = CHOLMOD_AMD;
00057
00058
00059 _cholmodCommon.supernodal = CHOLMOD_AUTO;
00060 batchEveryN = 100;
00061 }
00062
00063 virtual ~LinearSolverCholmodOnline()
00064 {
00065 delete _cholmodSparse;
00066 if (_cholmodFactor) {
00067 cholmod_free_factor(&_cholmodFactor, &_cholmodCommon);
00068 _cholmodFactor = 0;
00069 }
00070 cholmod_finish(&_cholmodCommon);
00071 }
00072
00073 virtual bool init()
00074 {
00075 return true;
00076 }
00077
00078 bool solve(const SparseBlockMatrix<MatrixType>& A, double* x, double* b)
00079 {
00080 cholmod_free_factor(&_cholmodFactor, &_cholmodCommon);
00081 _cholmodFactor = 0;
00082 fillCholmodExt(A, false);
00083
00084 computeSymbolicDecomposition(A);
00085 assert(_cholmodFactor && "Symbolic cholesky failed");
00086 double t=get_time();
00087
00088
00089 cholmod_dense bcholmod;
00090 bcholmod.nrow = bcholmod.d = _cholmodSparse->nrow;
00091 bcholmod.ncol = 1;
00092 bcholmod.x = b;
00093 bcholmod.xtype = CHOLMOD_REAL;
00094 bcholmod.dtype = CHOLMOD_DOUBLE;
00095
00096 cholmod_factorize(_cholmodSparse, _cholmodFactor, &_cholmodCommon);
00097 if (_cholmodCommon.status == CHOLMOD_NOT_POSDEF) {
00098 std::cerr << "solve(): Cholesky failure, writing debug.txt (Hessian loadable by Octave)" << std::endl;
00099 writeCCSMatrix("debug.txt", _cholmodSparse->nrow, _cholmodSparse->ncol, (int*)_cholmodSparse->p, (int*)_cholmodSparse->i, (double*)_cholmodSparse->x, true);
00100 return false;
00101 }
00102
00103 cholmod_dense* xcholmod = cholmod_solve(CHOLMOD_A, _cholmodFactor, &bcholmod, &_cholmodCommon);
00104 memcpy(x, xcholmod->x, sizeof(double) * bcholmod.nrow);
00105 cholmod_free_dense(&xcholmod, &_cholmodCommon);
00106
00107 if (globalStats){
00108 globalStats->timeNumericDecomposition = get_time() - t;
00109 globalStats->choleskyNNZ = _cholmodCommon.method[0].lnz;
00110 }
00111
00112 return true;
00113 }
00114
00115 bool blockOrdering() const { return true;}
00116
00117 cholmod_factor* L() const { return _cholmodFactor;}
00118
00119 int choleskyUpdate(cholmod_sparse* update)
00120 {
00121 int result = cholmod_updown(1, update, _cholmodFactor, &_cholmodCommon);
00122
00123 if (_cholmodCommon.status == CHOLMOD_NOT_POSDEF) {
00124 std::cerr << "Cholesky failure, writing debug.txt (Hessian loadable by Octave)" << std::endl;
00125 writeCCSMatrix("debug.txt", _cholmodSparse->nrow, _cholmodSparse->ncol, (int*)_cholmodSparse->p, (int*)_cholmodSparse->i, (double*)_cholmodSparse->x, true);
00126 return 0;
00127 }
00128 return result;
00129 }
00130
00131 bool solve(double* x, double* b)
00132 {
00133
00134 cholmod_dense bcholmod;
00135 bcholmod.nrow = bcholmod.d = _cholmodSparse->nrow;
00136 bcholmod.ncol = 1;
00137 bcholmod.x = b;
00138 bcholmod.xtype = CHOLMOD_REAL;
00139 bcholmod.dtype = CHOLMOD_DOUBLE;
00140
00141 cholmod_dense* xcholmod = cholmod_solve(CHOLMOD_A, _cholmodFactor, &bcholmod, &_cholmodCommon);
00142 memcpy(x, xcholmod->x, sizeof(double) * bcholmod.nrow);
00143 cholmod_free_dense(&xcholmod, &_cholmodCommon);
00144 return true;
00145 }
00146
00147 protected:
00148
00149 cholmod_common _cholmodCommon;
00150 CholmodExt* _cholmodSparse;
00151 cholmod_factor* _cholmodFactor;
00152 bool _blockOrdering;
00153 MatrixStructure _matrixStructure;
00154 VectorXi _scalarPermutation, _blockPermutation;
00155
00156 public:
00157 void computeSymbolicDecomposition(const SparseBlockMatrix<MatrixType>& A)
00158 {
00159 double t = get_time();
00160
00161 A.fillBlockStructure(_matrixStructure);
00162
00163
00164 if (_blockPermutation.size() < _matrixStructure.n)
00165 _blockPermutation.resize(2*_matrixStructure.n);
00166
00167 int amdStatus = camd_order(_matrixStructure.n, _matrixStructure.Ap, _matrixStructure.Aii, _blockPermutation.data(), NULL, NULL, cmember->data());
00168 if (amdStatus != CAMD_OK) {
00169 std::cerr << "Error while computing ordering" << std::endl;
00170 }
00171
00172
00173 if (_scalarPermutation.size() == 0)
00174 _scalarPermutation.resize(_cholmodSparse->ncol);
00175 if (_scalarPermutation.size() < (int)_cholmodSparse->ncol)
00176 _scalarPermutation.resize(2*_cholmodSparse->ncol);
00177 size_t scalarIdx = 0;
00178 for (int i = 0; i < _matrixStructure.n; ++i) {
00179 const int& p = _blockPermutation(i);
00180 int base = A.colBaseOfBlock(p);
00181 int nCols = A.colsOfBlock(p);
00182 for (int j = 0; j < nCols; ++j)
00183 _scalarPermutation(scalarIdx++) = base++;
00184 }
00185
00186 for (; scalarIdx < _cholmodSparse->ncol; ++scalarIdx)
00187 _scalarPermutation(scalarIdx) = scalarIdx;
00188 assert(scalarIdx == _cholmodSparse->ncol);
00189
00190
00191 _cholmodCommon.nmethods = 1;
00192 _cholmodCommon.method[0].ordering = CHOLMOD_GIVEN;
00193 _cholmodFactor = cholmod_analyze_p(_cholmodSparse, _scalarPermutation.data(), NULL, 0, &_cholmodCommon);
00194
00195 if (globalStats)
00196 globalStats->timeSymbolicDecomposition = get_time() - t;
00197
00198 }
00199
00200 void fillCholmodExt(const SparseBlockMatrix<MatrixType>& A, bool onlyValues)
00201 {
00202 int blockDimension = MatrixType::RowsAtCompileTime;
00203 assert(blockDimension > 0);
00204
00205 size_t origN = A.cols();
00206 int additionalSpace = blockDimension * batchEveryN;
00207 size_t m = A.rows() + additionalSpace;
00208 size_t n = A.cols() + additionalSpace;
00209
00210 if (_cholmodSparse->columnsAllocated < n) {
00211
00212 _cholmodSparse->columnsAllocated = _cholmodSparse->columnsAllocated == 0 ? n : 2 * n;
00213 delete[] (int*)_cholmodSparse->p;
00214 _cholmodSparse->p = new int[_cholmodSparse->columnsAllocated+1];
00215 }
00216 if (! onlyValues) {
00217 size_t nzmax = A.nonZeros() + additionalSpace;
00218 if (_cholmodSparse->nzmax < nzmax) {
00219
00220 _cholmodSparse->nzmax = _cholmodSparse->nzmax == 0 ? nzmax : 2 * nzmax;
00221 delete[] (double*)_cholmodSparse->x;
00222 delete[] (int*)_cholmodSparse->i;
00223 _cholmodSparse->i = new int[_cholmodSparse->nzmax];
00224 _cholmodSparse->x = new double[_cholmodSparse->nzmax];
00225 }
00226 }
00227 _cholmodSparse->ncol = n;
00228 _cholmodSparse->nrow = m;
00229
00230 int nz = 0;
00231 if (onlyValues)
00232 nz = A.fillCCS((double*)_cholmodSparse->x, true);
00233 else
00234 nz = A.fillCCS((int*)_cholmodSparse->p, (int*)_cholmodSparse->i, (double*)_cholmodSparse->x, true);
00235
00236 int* cp = (int*)_cholmodSparse->p;
00237 int* ci = (int*)_cholmodSparse->i;
00238 double* cx = (double*)_cholmodSparse->x;
00239
00240 cp = &cp[origN];
00241 ci = &ci[nz];
00242 cx = &cx[nz];
00243
00244
00245 for (int i = 0; i < additionalSpace; ++i) {
00246 *cp++ = nz;
00247 *ci++ = origN + i;
00248 *cx++ = 1e-6;
00249 ++nz;
00250 }
00251 *cp = nz;
00252
00253 }
00254
00255 };
00256
00257 }
00258
00259 #endif