00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 namespace {
00020 template<typename MatrixType>
00021 inline void pcg_axy(const MatrixType& A, const Eigen::VectorXd& x, int xoff, Eigen::VectorXd& y, int yoff)
00022 {
00023 y.segment<MatrixType::RowsAtCompileTime>(yoff) = A * x.segment<MatrixType::ColsAtCompileTime>(xoff);
00024 }
00025
00026 template<>
00027 inline void pcg_axy(const Eigen::MatrixXd& A, const Eigen::VectorXd& x, int xoff, Eigen::VectorXd& y, int yoff)
00028 {
00029 y.segment(yoff, A.rows()) = A * x.segment(xoff, A.cols());
00030 }
00031
00032 template<typename MatrixType>
00033 inline void pcg_axpy(const MatrixType& A, const Eigen::VectorXd& x, int xoff, Eigen::VectorXd& y, int yoff)
00034 {
00035 y.segment<MatrixType::RowsAtCompileTime>(yoff) += A * x.segment<MatrixType::ColsAtCompileTime>(xoff);
00036 }
00037
00038 template<>
00039 inline void pcg_axpy(const Eigen::MatrixXd& A, const Eigen::VectorXd& x, int xoff, Eigen::VectorXd& y, int yoff)
00040 {
00041 y.segment(yoff, A.rows()) += A * x.segment(xoff, A.cols());
00042 }
00043
00044 template<typename MatrixType>
00045 inline void pcg_atxpy(const MatrixType& A, const Eigen::VectorXd& x, int xoff, Eigen::VectorXd& y, int yoff)
00046 {
00047 y.segment<MatrixType::ColsAtCompileTime>(yoff) += A.transpose() * x.segment<MatrixType::RowsAtCompileTime>(xoff);
00048 }
00049
00050 template<>
00051 inline void pcg_atxpy(const Eigen::MatrixXd& A, const Eigen::VectorXd& x, int xoff, Eigen::VectorXd& y, int yoff)
00052 {
00053 y.segment(yoff, A.cols()) += A.transpose() * x.segment(xoff, A.rows());
00054 }
00055 }
00056
00057
00058 template <typename MatrixType>
00059 bool LinearSolverPCG<MatrixType>::solve(const SparseBlockMatrix<MatrixType>& A, double* x, double* b)
00060 {
00061 const bool indexRequired = _indices.size() == 0;
00062 _diag.clear();
00063 _J.clear();
00064
00065
00066 int colIdx = 0;
00067 for (size_t i = 0; i < A.blockCols().size(); ++i){
00068 const typename SparseBlockMatrix<MatrixType>::IntBlockMap& col = A.blockCols()[i];
00069 if (col.size() > 0) {
00070 typename SparseBlockMatrix<MatrixType>::IntBlockMap::const_iterator it;
00071 for (it = col.begin(); it != col.end(); ++it) {
00072 if (it->first == (int)i) {
00073 _diag.push_back(it->second);
00074 _J.push_back(it->second->inverse());
00075 break;
00076 }
00077 if (indexRequired) {
00078 _indices.push_back(std::make_pair(it->first > 0 ? A.rowBlockIndices()[it->first-1] : 0, colIdx));
00079 _sparseMat.push_back(it->second);
00080 }
00081
00082 }
00083 }
00084 colIdx = A.colBlockIndices()[i];
00085 }
00086
00087 int n = A.rows();
00088 Eigen::Map<Eigen::VectorXd> xvec(x, A.cols());
00089 const Eigen::Map<Eigen::VectorXd> bvec(b, n);
00090 xvec.setZero();
00091
00092 Eigen::VectorXd r, d, q, s;
00093 d.setZero(n);
00094 q.setZero(n);
00095 s.setZero(n);
00096
00097 r = bvec;
00098 multDiag(A.colBlockIndices(), _J, r, d);
00099 double dn = r.dot(d);
00100 double d0 = _tolerance * dn;
00101
00102 if (_absoluteTolerance) {
00103 if (_residual > 0.0 && _residual > d0)
00104 d0 = _residual;
00105 }
00106
00107 int maxIter = _maxIter < 0 ? A.rows() : _maxIter;
00108
00109 int iteration;
00110 for (iteration = 0; iteration < maxIter; ++iteration) {
00111 if (_verbose)
00112 std::cerr << "residual[" << iteration << "]: " << dn << std::endl;
00113 if (dn <= d0)
00114 break;
00115 mult(A.colBlockIndices(), d, q);
00116 double a = dn / d.dot(q);
00117 xvec += a*d;
00118
00119 r -= a*q;
00120 multDiag(A.colBlockIndices(), _J, r, s);
00121 double dold = dn;
00122 dn = r.dot(s);
00123 double ba = dn / dold;
00124 d = s + ba*d;
00125 }
00126
00127 _residual = 0.5 * dn;
00128 if (globalStats) {
00129 globalStats->iterationsLinearSolver = iteration;
00130 }
00131
00132 return true;
00133 }
00134
00135 template <typename MatrixType>
00136 void LinearSolverPCG<MatrixType>::multDiag(const std::vector<int>& colBlockIndices, MatrixVector& A, const Eigen::VectorXd& src, Eigen::VectorXd& dest)
00137 {
00138 int row = 0;
00139 for (size_t i = 0; i < A.size(); ++i) {
00140 pcg_axy(A[i], src, row, dest, row);
00141 row = colBlockIndices[i];
00142 }
00143 }
00144
00145 template <typename MatrixType>
00146 void LinearSolverPCG<MatrixType>::multDiag(const std::vector<int>& colBlockIndices, MatrixPtrVector& A, const Eigen::VectorXd& src, Eigen::VectorXd& dest)
00147 {
00148 int row = 0;
00149 for (size_t i = 0; i < A.size(); ++i) {
00150 pcg_axy(*A[i], src, row, dest, row);
00151 row = colBlockIndices[i];
00152 }
00153 }
00154
00155 template <typename MatrixType>
00156 void LinearSolverPCG<MatrixType>::mult(const std::vector<int>& colBlockIndices, const Eigen::VectorXd& src, Eigen::VectorXd& dest)
00157 {
00158
00159 multDiag(colBlockIndices, _diag, src, dest);
00160
00161
00162 for (size_t i = 0; i < _sparseMat.size(); ++i) {
00163 const int& srcOffset = _indices[i].second;
00164 const int& destOffsetT = srcOffset;
00165 const int& destOffset = _indices[i].first;
00166 const int& srcOffsetT = destOffset;
00167
00168 const typename SparseBlockMatrix<MatrixType>::SparseMatrixBlock* a = _sparseMat[i];
00169
00170 pcg_axpy(*a, src, srcOffset, dest, destOffset);
00171
00172 pcg_atxpy(*a, src, srcOffsetT, dest, destOffsetT);
00173 }
00174 }