#include <eiquadprog-rt.hpp>
Public Member Functions | |
const RtVectorX< nIneqCon+nEqCon >::i & | getActiveSet () const |
int | getActiveSetSize () const |
int | getIteratios () const |
const RtVectorX< nIneqCon+nEqCon >::d & | getLagrangeMultipliers () const |
int | getMaxIter () const |
double | getObjValue () const |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | RtEiquadprog () |
bool | setMaxIter (int maxIter) |
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) |
virtual | ~RtEiquadprog () |
Public Attributes | |
bool | is_inverse_provided_ |
RtMatrixX< nVars, nVars >::d | m_J |
Private Member Functions | |
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) |
void | compute_d (typename RtVectorX< nVars >::d &d, const typename RtMatrixX< nVars, nVars >::d &J, const typename RtVectorX< nVars >::d &np) |
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) |
template<typename Scalar > | |
Scalar | distance (Scalar a, Scalar b) |
void | update_r (const typename RtMatrixX< nVars, nVars >::d &R, typename RtVectorX< nIneqCon+nEqCon >::d &r, const typename RtVectorX< nVars >::d &d, int iq) |
void | update_z (typename RtVectorX< nVars >::d &z, const typename RtMatrixX< nVars, nVars >::d &J, const typename RtVectorX< nVars >::d &d, int iq) |
Private Attributes | |
RtVectorX< nIneqCon+nEqCon >::i | A |
RtVectorX< nIneqCon+nEqCon >::i | A_old |
Eigen::LLT< typename RtMatrixX< nVars, nVars >::d, Eigen::Lower > | chol_ |
current value of cost function More... | |
RtVectorX< nVars >::d | d |
J' np. More... | |
double | f_value |
max number of active-set iterations More... | |
RtVectorX< nIneqCon >::i | iaexcl |
RtVectorX< nIneqCon >::i | iai |
int | iter |
number of active-set iterations More... | |
int | m_maxIter |
RtVectorX< nVars >::d | np |
current constraint normal More... | |
int | q |
RtMatrixX< nVars, nVars >::d | R |
RtVectorX< nIneqCon+nEqCon >::d | r |
infeasibility multipliers, i.e. negative step direction in dual space More... | |
RtVectorX< nIneqCon >::d | s |
CI*x+ci0. More... | |
double | solver_return_ |
RtVectorX< nIneqCon+nEqCon >::d | u |
Lagrange multipliers. More... | |
RtVectorX< nIneqCon+nEqCon >::d | u_old |
RtVectorX< nVars >::d | x_old |
RtVectorX< nVars >::d | z |
step direction in primal space More... | |
Definition at line 89 of file eiquadprog-rt.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::RtEiquadprog | ( | ) |
|
virtual |
|
private |
|
inlineprivate |
Definition at line 234 of file eiquadprog-rt.hpp.
|
private |
|
inlineprivate |
Definition at line 220 of file eiquadprog-rt.hpp.
|
inline |
Return the active set, namely the indeces of active constraints. The first nEqCon indexes are for the equalities and are negative. The last nIneqCon indexes are for the inequalities and start from 0. Only the first q elements of the return vector are valid, where q is the size of the active set.
Definition at line 136 of file eiquadprog-rt.hpp.
|
inline |
Definition at line 108 of file eiquadprog-rt.hpp.
|
inline |
Definition at line 113 of file eiquadprog-rt.hpp.
|
inline |
Definition at line 123 of file eiquadprog-rt.hpp.
|
inline |
Definition at line 96 of file eiquadprog-rt.hpp.
|
inline |
Definition at line 118 of file eiquadprog-rt.hpp.
|
inline |
Definition at line 98 of file eiquadprog-rt.hpp.
RtEiquadprog_status eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::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 | ||
) |
solves the problem min. x' Hess x + 2 g0' x s.t. CE x + ce0 = 0 CI x + ci0 >= 0
|
inlineprivate |
Definition at line 254 of file eiquadprog-rt.hpp.
|
inlineprivate |
Definition at line 244 of file eiquadprog-rt.hpp.
|
private |
active set (indeces of active constraints) the first nEqCon indeces are for the equalities and are negative the last nIneqCon indeces are for the inequalities are start from 0
Definition at line 190 of file eiquadprog-rt.hpp.
|
private |
Definition at line 206 of file eiquadprog-rt.hpp.
|
private |
current value of cost function
Definition at line 162 of file eiquadprog-rt.hpp.
|
private |
J' np.
Definition at line 182 of file eiquadprog-rt.hpp.
|
private |
max number of active-set iterations
Definition at line 160 of file eiquadprog-rt.hpp.
|
private |
initialized as [1, ..., 1, .] if iaexcl(i)!=1 inequality constraint i cannot be added to the active set if adding ineq constraint i fails => iaexcl(i)=0 iaexcl(i)=0 iff ineq constraint i is linearly dependent to other active constraints iaexcl(i)=1 otherwise
Definition at line 202 of file eiquadprog-rt.hpp.
|
private |
initialized as K \ A iai(i)=-1 iff inequality constraint i is in the active set iai(i)=i otherwise
Definition at line 195 of file eiquadprog-rt.hpp.
bool eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::is_inverse_provided_ |
Definition at line 156 of file eiquadprog-rt.hpp.
|
private |
number of active-set iterations
Definition at line 217 of file eiquadprog-rt.hpp.
RtMatrixX<nVars, nVars>::d eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::m_J |
Definition at line 155 of file eiquadprog-rt.hpp.
|
private |
Definition at line 159 of file eiquadprog-rt.hpp.
|
private |
current constraint normal
Definition at line 185 of file eiquadprog-rt.hpp.
|
private |
size of the active set A (containing the indices of the active constraints)
Definition at line 214 of file eiquadprog-rt.hpp.
|
private |
from QR of L' N, where L is Cholewsky factor of Hessian, and N is the matrix of active constraints
Definition at line 167 of file eiquadprog-rt.hpp.
|
private |
infeasibility multipliers, i.e. negative step direction in dual space
Definition at line 173 of file eiquadprog-rt.hpp.
|
private |
CI*x+ci0.
Definition at line 170 of file eiquadprog-rt.hpp.
|
private |
Definition at line 163 of file eiquadprog-rt.hpp.
|
private |
Lagrange multipliers.
Definition at line 176 of file eiquadprog-rt.hpp.
|
private |
Definition at line 205 of file eiquadprog-rt.hpp.
|
private |
Definition at line 204 of file eiquadprog-rt.hpp.
|
private |
step direction in primal space
Definition at line 179 of file eiquadprog-rt.hpp.