Go to the documentation of this file.
19 #ifndef __eiquadprog_rt_hpp__
20 #define __eiquadprog_rt_hpp__
22 #include <Eigen/Dense>
24 #include "eiquadprog/eiquadprog-utils.hxx"
26 #define OPTIMIZE_STEP_1_2 // compute s(x) = ci^T * x + ci0
27 #define OPTIMIZE_COMPUTE_D // use noalias
28 #define OPTIMIZE_UPDATE_Z // use noalias
29 #define OPTIMIZE_HESSIAN_INVERSE // use solveInPlace
30 #define OPTIMIZE_UNCONSTR_MINIM
35 #define DEBUG_STREAM(msg)
37 #ifdef PROFILE_EIQUADPROG
38 #define START_PROFILER_EIQUADPROG_RT(x) START_PROFILER(x)
39 #define STOP_PROFILER_EIQUADPROG_RT(x) STOP_PROFILER(x)
41 #define START_PROFILER_EIQUADPROG_RT(x)
42 #define STOP_PROFILER_EIQUADPROG_RT(x)
45 #define PROFILE_EIQUADPROG_CHOWLESKY_DECOMPOSITION "EIQUADPROG_RT Chowlesky dec"
46 #define PROFILE_EIQUADPROG_CHOWLESKY_INVERSE "EIQUADPROG_RT Chowlesky inv"
47 #define PROFILE_EIQUADPROG_ADD_EQ_CONSTR "EIQUADPROG_RT ADD_EQ_CONSTR"
48 #define PROFILE_EIQUADPROG_ADD_EQ_CONSTR_1 "EIQUADPROG_RT ADD_EQ_CONSTR_1"
49 #define PROFILE_EIQUADPROG_ADD_EQ_CONSTR_2 "EIQUADPROG_RT ADD_EQ_CONSTR_2"
50 #define PROFILE_EIQUADPROG_STEP_1 "EIQUADPROG_RT STEP_1"
51 #define PROFILE_EIQUADPROG_STEP_1_1 "EIQUADPROG_RT STEP_1_1"
52 #define PROFILE_EIQUADPROG_STEP_1_2 "EIQUADPROG_RT STEP_1_2"
53 #define PROFILE_EIQUADPROG_STEP_1_UNCONSTR_MINIM \
54 "EIQUADPROG_RT STEP_1_UNCONSTR_MINIM"
55 #define PROFILE_EIQUADPROG_STEP_2 "EIQUADPROG_RT STEP_2"
56 #define PROFILE_EIQUADPROG_STEP_2A "EIQUADPROG_RT STEP_2A"
57 #define PROFILE_EIQUADPROG_STEP_2B "EIQUADPROG_RT STEP_2B"
58 #define PROFILE_EIQUADPROG_STEP_2C "EIQUADPROG_RT STEP_2C"
60 #define DEFAULT_MAX_ITER 1000
62 template <
int Rows,
int Cols>
64 typedef Eigen::Matrix<double, Rows, Cols>
d;
69 typedef Eigen::Matrix<double, Rows, 1>
d;
70 typedef Eigen::Matrix<int, Rows, 1>
i;
88 template <
int nVars,
int nEqCon,
int nIneqCon>
91 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
99 if (maxIter < 0)
return false;
162 Eigen::LLT<typename RtMatrixX<nVars, nVars>::d, Eigen::Lower>
chol_;
208 #ifdef OPTIMIZE_ADD_CONSTRAINT
219 template <
typename Scalar>
226 return a1 * std::sqrt(1.0 + t * t);
227 }
else if (b1 > a1) {
229 return b1 * std::sqrt(1.0 + t * t);
231 return a1 * std::sqrt(2.0);
237 #ifdef OPTIMIZE_COMPUTE_D
238 d.noalias() = J.adjoint() *
np;
240 d = J.adjoint() *
np;
247 #ifdef OPTIMIZE_UPDATE_Z
248 z.noalias() = J.rightCols(nVars - iq) *
d.tail(nVars - iq);
250 z = J.rightCols(J.cols() - iq) *
d.tail(J.cols() - iq);
257 r.head(iq) =
d.head(iq);
258 R.topLeftCorner(iq, iq)
259 .template triangularView<Eigen::Upper>()
260 .solveInPlace(
r.head(iq));
277 #include "eiquadprog/eiquadprog-rt.hxx"
void compute_d(typename RtVectorX< nVars >::d &d, const typename RtMatrixX< nVars, nVars >::d &J, const typename RtVectorX< nVars >::d &np)
RtVectorX< nIneqCon+nEqCon >::d r
infeasibility multipliers, i.e. negative step direction in dual space
RtVectorX< nIneqCon >::i iai
RtVectorX< nIneqCon >::i iaexcl
const RtVectorX< nIneqCon+nEqCon >::i & getActiveSet() const
RtVectorX< nIneqCon >::d s
CI*x+ci0.
Eigen::Matrix< int, Rows, 1 > i
Scalar distance(Scalar a, Scalar b)
@ RT_EIQUADPROG_REDUNDANT_EQUALITIES
RtEiquadprog_status solve_quadprog(const typename RtMatrixX< nVars, nVars >::d &Hess, const typename RtVectorX< nVars >::d &g0, const typename RtMatrixX< nEqCon, nVars >::d &CE, const typename RtVectorX< nEqCon >::d &ce0, const typename RtMatrixX< nIneqCon, nVars >::d &CI, const typename RtVectorX< nIneqCon >::d &ci0, typename RtVectorX< nVars >::d &x)
double f_value
max number of active-set iterations
RtVectorX< nIneqCon+nEqCon >::d u
Lagrange multipliers.
RtVectorX< nVars >::d z
step direction in primal space
RtMatrixX< nVars, nVars >::d m_J
RtVectorX< nVars >::d x_old
RtVectorX< nVars >::d np
current constraint normal
RtVectorX< nIneqCon+nEqCon >::d u_old
bool setMaxIter(int maxIter)
@ RT_EIQUADPROG_INFEASIBLE
int iter
number of active-set iterations
@ RT_EIQUADPROG_MAX_ITER_REACHED
void delete_constraint(typename RtMatrixX< nVars, nVars >::d &R, typename RtMatrixX< nVars, nVars >::d &J, typename RtVectorX< nIneqCon+nEqCon >::i &A, typename RtVectorX< nIneqCon+nEqCon >::d &u, int &iq, int l)
const RtVectorX< nIneqCon+nEqCon >::d & getLagrangeMultipliers() const
RtVectorX< nIneqCon+nEqCon >::i A_old
RtVectorX< nIneqCon+nEqCon >::i A
bool add_constraint(typename RtMatrixX< nVars, nVars >::d &R, typename RtMatrixX< nVars, nVars >::d &J, typename RtVectorX< nVars >::d &d, int &iq, double &R_norm)
Eigen::LLT< typename RtMatrixX< nVars, nVars >::d, Eigen::Lower > chol_
current value of cost function
bool is_inverse_provided_
Eigen::Matrix< double, Rows, Cols > d
@ RT_EIQUADPROG_UNBOUNDED
double getObjValue() const
RtVectorX< nVars >::d d
J' np.
void update_r(const typename RtMatrixX< nVars, nVars >::d &R, typename RtVectorX< nIneqCon+nEqCon >::d &r, const typename RtVectorX< nVars >::d &d, int iq)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW RtEiquadprog()
RtMatrixX< nVars, nVars >::d R
Eigen::Matrix< double, Rows, 1 > d
int getActiveSetSize() const
void update_z(typename RtVectorX< nVars >::d &z, const typename RtMatrixX< nVars, nVars >::d &J, const typename RtVectorX< nVars >::d &d, int iq)
eiquadprog
Author(s): Gabriele Buondonno, Andrea Del Prete, Luca Di Gaspero, Angelo Furfaro, Benjamin Stephens, Gael Guennebaud
autogenerated on Wed May 28 2025 02:55:57