Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #include "../../../../Eigen/src/Core/util/NonMPL2.h"
00034
00035 #ifndef EIGEN_CONSTRAINEDCG_H
00036 #define EIGEN_CONSTRAINEDCG_H
00037
00038 #include <Eigen/Core>
00039
00040 namespace Eigen {
00041
00042 namespace internal {
00043
00050 template <typename CMatrix, typename CINVMatrix>
00051 void pseudo_inverse(const CMatrix &C, CINVMatrix &CINV)
00052 {
00053
00054 typedef typename CMatrix::Scalar Scalar;
00055 typedef typename CMatrix::Index Index;
00056
00057 typedef Matrix<Scalar,Dynamic,1> TmpVec;
00058
00059 Index rows = C.rows(), cols = C.cols();
00060
00061 TmpVec d(rows), e(rows), l(cols), p(rows), q(rows), r(rows);
00062 Scalar rho, rho_1, alpha;
00063 d.setZero();
00064
00065 CINV.startFill();
00066 for (Index i = 0; i < rows; ++i)
00067 {
00068 d[i] = 1.0;
00069 rho = 1.0;
00070 e.setZero();
00071 r = d;
00072 p = d;
00073
00074 while (rho >= 1e-38)
00075 {
00076
00077 l = C.transpose() * p;
00078 q = C * l;
00079 alpha = rho / p.dot(q);
00080 e += alpha * p;
00081 r += -alpha * q;
00082 rho_1 = rho;
00083 rho = r.dot(r);
00084 p = (rho/rho_1) * p + r;
00085 }
00086
00087 l = C.transpose() * e;
00088
00089 for (Index j=0; j<l.size(); ++j)
00090 if (l[j]<1e-15)
00091 CINV.fill(i,j) = l[j];
00092
00093 d[i] = 0.0;
00094 }
00095 CINV.endFill();
00096 }
00097
00098
00099
00105 template<typename TMatrix, typename CMatrix,
00106 typename VectorX, typename VectorB, typename VectorF>
00107 void constrained_cg(const TMatrix& A, const CMatrix& C, VectorX& x,
00108 const VectorB& b, const VectorF& f, IterationController &iter)
00109 {
00110 typedef typename TMatrix::Scalar Scalar;
00111 typedef typename TMatrix::Index Index;
00112 typedef Matrix<Scalar,Dynamic,1> TmpVec;
00113
00114 Scalar rho = 1.0, rho_1, lambda, gamma;
00115 Index xSize = x.size();
00116 TmpVec p(xSize), q(xSize), q2(xSize),
00117 r(xSize), old_z(xSize), z(xSize),
00118 memox(xSize);
00119 std::vector<bool> satured(C.rows());
00120 p.setZero();
00121 iter.setRhsNorm(sqrt(b.dot(b)));
00122 if (iter.rhsNorm() == 0.0) iter.setRhsNorm(1.0);
00123
00124 SparseMatrix<Scalar,RowMajor> CINV(C.rows(), C.cols());
00125 pseudo_inverse(C, CINV);
00126
00127 while(true)
00128 {
00129
00130 old_z = z;
00131 memox = x;
00132 r = b;
00133 r += A * -x;
00134 z = r;
00135 bool transition = false;
00136 for (Index i = 0; i < C.rows(); ++i)
00137 {
00138 Scalar al = C.row(i).dot(x) - f.coeff(i);
00139 if (al >= -1.0E-15)
00140 {
00141 if (!satured[i])
00142 {
00143 satured[i] = true;
00144 transition = true;
00145 }
00146 Scalar bb = CINV.row(i).dot(z);
00147 if (bb > 0.0)
00148
00149 for (typename CMatrix::InnerIterator it(C,i); it; ++it)
00150 z.coeffRef(it.index()) -= bb*it.value();
00151 }
00152 else
00153 satured[i] = false;
00154 }
00155
00156
00157 rho_1 = rho;
00158 rho = r.dot(z);
00159
00160 if (iter.finished(rho)) break;
00161
00162 if (iter.noiseLevel() > 0 && transition) std::cerr << "CCG: transition\n";
00163 if (transition || iter.first()) gamma = 0.0;
00164 else gamma = (std::max)(0.0, (rho - old_z.dot(z)) / rho_1);
00165 p = z + gamma*p;
00166
00167 ++iter;
00168
00169 q = A * p;
00170 lambda = rho / q.dot(p);
00171 for (Index i = 0; i < C.rows(); ++i)
00172 {
00173 if (!satured[i])
00174 {
00175 Scalar bb = C.row(i).dot(p) - f[i];
00176 if (bb > 0.0)
00177 lambda = (std::min)(lambda, (f.coeff(i)-C.row(i).dot(x)) / bb);
00178 }
00179 }
00180 x += lambda * p;
00181 memox -= x;
00182 }
00183 }
00184
00185 }
00186
00187 }
00188
00189 #endif // EIGEN_CONSTRAINEDCG_H