00001 #ifndef _EIGEN_QUADSOLVE_HPP_
00002 #define _EIGEN_QUADSOLVE_HPP_
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
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084 #include <Eigen/Dense>
00085
00086 namespace Eigen {
00087
00088
00089
00090 template<typename Scalar>
00091 inline Scalar distance(Scalar a, Scalar b)
00092 {
00093 Scalar a1, b1, t;
00094 a1 = std::abs(a);
00095 b1 = std::abs(b);
00096 if (a1 > b1)
00097 {
00098 t = (b1 / a1);
00099 return a1 * std::sqrt(1.0 + t * t);
00100 }
00101 else
00102 if (b1 > a1)
00103 {
00104 t = (a1 / b1);
00105 return b1 * std::sqrt(1.0 + t * t);
00106 }
00107 return a1 * std::sqrt(2.0);
00108 }
00109
00110
00111
00112 inline void compute_d(VectorXd &d, const MatrixXd& J, const VectorXd& np)
00113 {
00114 d = J.adjoint() * np;
00115 }
00116
00117 inline void update_z(VectorXd& z, const MatrixXd& J, const VectorXd& d, int iq)
00118 {
00119 z = J.rightCols(z.size()-iq) * d.tail(d.size()-iq);
00120 }
00121
00122 inline void update_r(const MatrixXd& R, VectorXd& r, const VectorXd& d, int iq)
00123 {
00124 r.head(iq)= R.topLeftCorner(iq,iq).triangularView<Upper>().solve(d.head(iq));
00125 }
00126
00127 bool add_constraint(MatrixXd& R, MatrixXd& J, VectorXd& d, int& iq, double& R_norm);
00128 void delete_constraint(MatrixXd& R, MatrixXd& J, VectorXi& A, VectorXd& u, int p, int& iq, int l);
00129
00130
00131 inline double solve_quadprog(MatrixXd & G, VectorXd & g0,
00132 const MatrixXd & CE, const VectorXd & ce0,
00133 const MatrixXd & CI, const VectorXd & ci0,
00134 VectorXd& x)
00135 {
00136 int i, j, k, l;
00137 int ip, me, mi;
00138 int n=g0.size(); int p=ce0.size(); int m=ci0.size();
00139 MatrixXd R(G.rows(),G.cols()), J(G.rows(),G.cols());
00140
00141 LLT<MatrixXd,Lower> chol(G.cols());
00142
00143 VectorXd s(m+p), z(n), r(m + p), d(n), np(n), u(m + p);
00144 VectorXd x_old(n), u_old(m + p);
00145 double f_value, psi, c1, c2, sum, ss, R_norm;
00146 const double inf = std::numeric_limits<double>::infinity();
00147 double t, t1, t2;
00148
00149 VectorXi A(m + p), A_old(m + p), iai(m + p);
00150 int q;
00151 int iq, iter = 0;
00152 bool iaexcl[m + p];
00153
00154 me = p;
00155 mi = m;
00156 q = 0;
00157
00158
00159
00160
00161
00162
00163 c1 = G.trace();
00164
00165
00166 chol.compute(G);
00167
00168
00169 d.setZero();
00170 R.setZero();
00171 R_norm = 1.0;
00172
00173
00174
00175 J.setIdentity();
00176 J = chol.matrixU().solve(J);
00177 c2 = J.trace();
00178 #ifdef TRACE_SOLVER
00179 print_matrix("J", J, n);
00180 #endif
00181
00182
00183
00184
00185
00186
00187
00188
00189 x = chol.solve(g0);
00190 x = -x;
00191
00192 f_value = 0.5 * g0.dot(x);
00193 #ifdef TRACE_SOLVER
00194 std::cerr << "Unconstrained solution: " << f_value << std::endl;
00195 print_vector("x", x, n);
00196 #endif
00197
00198
00199 iq = 0;
00200 for (i = 0; i < me; i++)
00201 {
00202 np = CE.col(i);
00203 compute_d(d, J, np);
00204 update_z(z, J, d, iq);
00205 update_r(R, r, d, iq);
00206 #ifdef TRACE_SOLVER
00207 print_matrix("R", R, iq);
00208 print_vector("z", z, n);
00209 print_vector("r", r, iq);
00210 print_vector("d", d, n);
00211 #endif
00212
00213
00214
00215 t2 = 0.0;
00216 if (std::abs(z.dot(z)) > std::numeric_limits<double>::epsilon())
00217 t2 = (-np.dot(x) - ce0(i)) / z.dot(np);
00218
00219 x += t2 * z;
00220
00221
00222 u(iq) = t2;
00223 u.head(iq) -= t2 * r.head(iq);
00224
00225
00226 f_value += 0.5 * (t2 * t2) * z.dot(np);
00227 A(i) = -i - 1;
00228
00229 if (!add_constraint(R, J, d, iq, R_norm))
00230 {
00231
00232
00233 return f_value;
00234 }
00235 }
00236
00237
00238 for (i = 0; i < mi; i++)
00239 iai(i) = i;
00240
00241 l1: iter++;
00242 #ifdef TRACE_SOLVER
00243 print_vector("x", x, n);
00244 #endif
00245
00246 for (i = me; i < iq; i++)
00247 {
00248 ip = A(i);
00249 iai(ip) = -1;
00250 }
00251
00252
00253 ss = 0.0;
00254 psi = 0.0;
00255 ip = 0;
00256 for (i = 0; i < mi; i++)
00257 {
00258 iaexcl[i] = true;
00259 sum = CI.col(i).dot(x) + ci0(i);
00260 s(i) = sum;
00261 psi += std::min(0.0, sum);
00262 }
00263 #ifdef TRACE_SOLVER
00264 print_vector("s", s, mi);
00265 #endif
00266
00267
00268 if (std::abs(psi) <= mi * std::numeric_limits<double>::epsilon() * c1 * c2* 100.0)
00269 {
00270
00271 q = iq;
00272 return f_value;
00273 }
00274
00275
00276 u_old.head(iq) = u.head(iq);
00277 A_old.head(iq) = A.head(iq);
00278 x_old = x;
00279
00280 l2:
00281 for (i = 0; i < mi; i++)
00282 {
00283 if (s(i) < ss && iai(i) != -1 && iaexcl[i])
00284 {
00285 ss = s(i);
00286 ip = i;
00287 }
00288 }
00289 if (ss >= 0.0)
00290 {
00291 q = iq;
00292 return f_value;
00293 }
00294
00295
00296 np = CI.col(ip);
00297
00298 u(iq) = 0.0;
00299
00300 A(iq) = ip;
00301
00302 #ifdef TRACE_SOLVER
00303 std::cerr << "Trying with constraint " << ip << std::endl;
00304 print_vector("np", np, n);
00305 #endif
00306
00307 l2a:
00308
00309 compute_d(d, J, np);
00310 update_z(z, J, d, iq);
00311
00312 update_r(R, r, d, iq);
00313 #ifdef TRACE_SOLVER
00314 std::cerr << "Step direction z" << std::endl;
00315 print_vector("z", z, n);
00316 print_vector("r", r, iq + 1);
00317 print_vector("u", u, iq + 1);
00318 print_vector("d", d, n);
00319 print_ivector("A", A, iq + 1);
00320 #endif
00321
00322
00323 l = 0;
00324
00325 t1 = inf;
00326
00327 for (k = me; k < iq; k++)
00328 {
00329 double tmp;
00330 if (r(k) > 0.0 && ((tmp = u(k) / r(k)) < t1) )
00331 {
00332 t1 = tmp;
00333 l = A(k);
00334 }
00335 }
00336
00337 if (std::abs(z.dot(z)) > std::numeric_limits<double>::epsilon())
00338 t2 = -s(ip) / z.dot(np);
00339 else
00340 t2 = inf;
00341
00342
00343 t = std::min(t1, t2);
00344 #ifdef TRACE_SOLVER
00345 std::cerr << "Step sizes: " << t << " (t1 = " << t1 << ", t2 = " << t2 << ") ";
00346 #endif
00347
00348
00349
00350
00351 if (t >= inf)
00352 {
00353
00354
00355 q = iq;
00356 return inf;
00357 }
00358
00359 if (t2 >= inf)
00360 {
00361
00362 u.head(iq) -= t * r.head(iq);
00363 u(iq) += t;
00364 iai(l) = l;
00365 delete_constraint(R, J, A, u, p, iq, l);
00366 #ifdef TRACE_SOLVER
00367 std::cerr << " in dual space: "
00368 << f_value << std::endl;
00369 print_vector("x", x, n);
00370 print_vector("z", z, n);
00371 print_ivector("A", A, iq + 1);
00372 #endif
00373 goto l2a;
00374 }
00375
00376
00377
00378 x += t * z;
00379
00380 f_value += t * z.dot(np) * (0.5 * t + u(iq));
00381
00382 u.head(iq) -= t * r.head(iq);
00383 u(iq) += t;
00384 #ifdef TRACE_SOLVER
00385 std::cerr << " in both spaces: "
00386 << f_value << std::endl;
00387 print_vector("x", x, n);
00388 print_vector("u", u, iq + 1);
00389 print_vector("r", r, iq + 1);
00390 print_ivector("A", A, iq + 1);
00391 #endif
00392
00393 if (t == t2)
00394 {
00395 #ifdef TRACE_SOLVER
00396 std::cerr << "Full step has taken " << t << std::endl;
00397 print_vector("x", x, n);
00398 #endif
00399
00400
00401 if (!add_constraint(R, J, d, iq, R_norm))
00402 {
00403 iaexcl[ip] = false;
00404 delete_constraint(R, J, A, u, p, iq, ip);
00405 #ifdef TRACE_SOLVER
00406 print_matrix("R", R, n);
00407 print_ivector("A", A, iq);
00408 #endif
00409 for (i = 0; i < m; i++)
00410 iai(i) = i;
00411 for (i = 0; i < iq; i++)
00412 {
00413 A(i) = A_old(i);
00414 iai(A(i)) = -1;
00415 u(i) = u_old(i);
00416 }
00417 x = x_old;
00418 goto l2;
00419 }
00420 else
00421 iai(ip) = -1;
00422 #ifdef TRACE_SOLVER
00423 print_matrix("R", R, n);
00424 print_ivector("A", A, iq);
00425 #endif
00426 goto l1;
00427 }
00428
00429
00430 #ifdef TRACE_SOLVER
00431 std::cerr << "Partial step has taken " << t << std::endl;
00432 print_vector("x", x, n);
00433 #endif
00434
00435 iai(l) = l;
00436 delete_constraint(R, J, A, u, p, iq, l);
00437 #ifdef TRACE_SOLVER
00438 print_matrix("R", R, n);
00439 print_ivector("A", A, iq);
00440 #endif
00441
00442 s(ip) = CI.col(ip).dot(x) + ci0(ip);
00443
00444 #ifdef TRACE_SOLVER
00445 print_vector("s", s, mi);
00446 #endif
00447 goto l2a;
00448 }
00449
00450
00451 inline bool add_constraint(MatrixXd& R, MatrixXd& J, VectorXd& d, int& iq, double& R_norm)
00452 {
00453 int n=J.rows();
00454 #ifdef TRACE_SOLVER
00455 std::cerr << "Add constraint " << iq << '/';
00456 #endif
00457 int i, j, k;
00458 double cc, ss, h, t1, t2, xny;
00459
00460
00461
00462
00463
00464 for (j = n - 1; j >= iq + 1; j--)
00465 {
00466
00467
00468
00469
00470
00471
00472
00473
00474 cc = d(j - 1);
00475 ss = d(j);
00476 h = distance(cc, ss);
00477 if (h == 0.0)
00478 continue;
00479 d(j) = 0.0;
00480 ss = ss / h;
00481 cc = cc / h;
00482 if (cc < 0.0)
00483 {
00484 cc = -cc;
00485 ss = -ss;
00486 d(j - 1) = -h;
00487 }
00488 else
00489 d(j - 1) = h;
00490 xny = ss / (1.0 + cc);
00491 for (k = 0; k < n; k++)
00492 {
00493 t1 = J(k,j - 1);
00494 t2 = J(k,j);
00495 J(k,j - 1) = t1 * cc + t2 * ss;
00496 J(k,j) = xny * (t1 + J(k,j - 1)) - t2;
00497 }
00498 }
00499
00500 iq++;
00501
00502
00503
00504 R.col(iq-1).head(iq) = d.head(iq);
00505 #ifdef TRACE_SOLVER
00506 std::cerr << iq << std::endl;
00507 #endif
00508
00509 if (std::abs(d(iq - 1)) <= std::numeric_limits<double>::epsilon() * R_norm)
00510
00511 return false;
00512 R_norm = std::max<double>(R_norm, std::abs(d(iq - 1)));
00513 return true;
00514 }
00515
00516
00517 inline void delete_constraint(MatrixXd& R, MatrixXd& J, VectorXi& A, VectorXd& u, int p, int& iq, int l)
00518 {
00519
00520 int n = R.rows();
00521 #ifdef TRACE_SOLVER
00522 std::cerr << "Delete constraint " << l << ' ' << iq;
00523 #endif
00524 int i, j, k, qq;
00525 double cc, ss, h, xny, t1, t2;
00526
00527
00528 for (i = p; i < iq; i++)
00529 if (A(i) == l)
00530 {
00531 qq = i;
00532 break;
00533 }
00534
00535
00536 for (i = qq; i < iq - 1; i++)
00537 {
00538 A(i) = A(i + 1);
00539 u(i) = u(i + 1);
00540 R.col(i) = R.col(i+1);
00541 }
00542
00543 A(iq - 1) = A(iq);
00544 u(iq - 1) = u(iq);
00545 A(iq) = 0;
00546 u(iq) = 0.0;
00547 for (j = 0; j < iq; j++)
00548 R(j,iq - 1) = 0.0;
00549
00550 iq--;
00551 #ifdef TRACE_SOLVER
00552 std::cerr << '/' << iq << std::endl;
00553 #endif
00554
00555 if (iq == 0)
00556 return;
00557
00558 for (j = qq; j < iq; j++)
00559 {
00560 cc = R(j,j);
00561 ss = R(j + 1,j);
00562 h = distance(cc, ss);
00563 if (h == 0.0)
00564 continue;
00565 cc = cc / h;
00566 ss = ss / h;
00567 R(j + 1,j) = 0.0;
00568 if (cc < 0.0)
00569 {
00570 R(j,j) = -h;
00571 cc = -cc;
00572 ss = -ss;
00573 }
00574 else
00575 R(j,j) = h;
00576
00577 xny = ss / (1.0 + cc);
00578 for (k = j + 1; k < iq; k++)
00579 {
00580 t1 = R(j,k);
00581 t2 = R(j + 1,k);
00582 R(j,k) = t1 * cc + t2 * ss;
00583 R(j + 1,k) = xny * (t1 + R(j,k)) - t2;
00584 }
00585 for (k = 0; k < n; k++)
00586 {
00587 t1 = J(k,j);
00588 t2 = J(k,j + 1);
00589 J(k,j) = t1 * cc + t2 * ss;
00590 J(k,j + 1) = xny * (J(k,j) + t1) - t2;
00591 }
00592 }
00593 }
00594
00595 }
00596
00597 #endif