Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon > Class Template Reference

#include <eiquadprog-rt.hpp>

Public Member Functions

const RtVectorX< nIneqCon+nEqCon >::i & getActiveSet () const
 
int getActiveSetSize () const
 
int getIteratios () const
 
const RtVectorX< nIneqCon+nEqCon >::dgetLagrangeMultipliers () 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...
 

Detailed Description

template<int nVars, int nEqCon, int nIneqCon>
class eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >

Definition at line 89 of file eiquadprog-rt.hpp.

Constructor & Destructor Documentation

◆ RtEiquadprog()

template<int nVars, int nEqCon, int nIneqCon>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::RtEiquadprog ( )

◆ ~RtEiquadprog()

template<int nVars, int nEqCon, int nIneqCon>
virtual eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::~RtEiquadprog ( )
virtual

Member Function Documentation

◆ add_constraint()

template<int nVars, int nEqCon, int nIneqCon>
bool eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::add_constraint ( typename RtMatrixX< nVars, nVars >::d R,
typename RtMatrixX< nVars, nVars >::d J,
typename RtVectorX< nVars >::d d,
int &  iq,
double &  R_norm 
)
private

◆ compute_d()

template<int nVars, int nEqCon, int nIneqCon>
void eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::compute_d ( typename RtVectorX< nVars >::d d,
const typename RtMatrixX< nVars, nVars >::d J,
const typename RtVectorX< nVars >::d np 
)
inlineprivate

Definition at line 234 of file eiquadprog-rt.hpp.

◆ delete_constraint()

template<int nVars, int nEqCon, int nIneqCon>
void eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::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 
)
private

◆ distance()

template<int nVars, int nEqCon, int nIneqCon>
template<typename Scalar >
Scalar eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::distance ( Scalar  a,
Scalar  b 
)
inlineprivate

Definition at line 220 of file eiquadprog-rt.hpp.

◆ getActiveSet()

template<int nVars, int nEqCon, int nIneqCon>
const RtVectorX<nIneqCon + nEqCon>::i& eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::getActiveSet ( ) const
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.

Returns
The set of indexes of the active constraints.

Definition at line 136 of file eiquadprog-rt.hpp.

◆ getActiveSetSize()

template<int nVars, int nEqCon, int nIneqCon>
int eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::getActiveSetSize ( ) const
inline
Returns
The size of the active set, namely the number of active constraints (including the equalities).

Definition at line 108 of file eiquadprog-rt.hpp.

◆ getIteratios()

template<int nVars, int nEqCon, int nIneqCon>
int eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::getIteratios ( ) const
inline
Returns
The number of active-set iteratios.

Definition at line 113 of file eiquadprog-rt.hpp.

◆ getLagrangeMultipliers()

template<int nVars, int nEqCon, int nIneqCon>
const RtVectorX<nIneqCon + nEqCon>::d& eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::getLagrangeMultipliers ( ) const
inline
Returns
The Lagrange multipliers

Definition at line 123 of file eiquadprog-rt.hpp.

◆ getMaxIter()

template<int nVars, int nEqCon, int nIneqCon>
int eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::getMaxIter ( ) const
inline

Definition at line 96 of file eiquadprog-rt.hpp.

◆ getObjValue()

template<int nVars, int nEqCon, int nIneqCon>
double eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::getObjValue ( ) const
inline
Returns
The value of the objective function.

Definition at line 118 of file eiquadprog-rt.hpp.

◆ setMaxIter()

template<int nVars, int nEqCon, int nIneqCon>
bool eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::setMaxIter ( int  maxIter)
inline

Definition at line 98 of file eiquadprog-rt.hpp.

◆ solve_quadprog()

template<int nVars, int nEqCon, int nIneqCon>
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

◆ update_r()

template<int nVars, int nEqCon, int nIneqCon>
void eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::update_r ( const typename RtMatrixX< nVars, nVars >::d R,
typename RtVectorX< nIneqCon+nEqCon >::d r,
const typename RtVectorX< nVars >::d d,
int  iq 
)
inlineprivate

Definition at line 254 of file eiquadprog-rt.hpp.

◆ update_z()

template<int nVars, int nEqCon, int nIneqCon>
void eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::update_z ( typename RtVectorX< nVars >::d z,
const typename RtMatrixX< nVars, nVars >::d J,
const typename RtVectorX< nVars >::d d,
int  iq 
)
inlineprivate

Definition at line 244 of file eiquadprog-rt.hpp.

Member Data Documentation

◆ A

template<int nVars, int nEqCon, int nIneqCon>
RtVectorX<nIneqCon + nEqCon>::i eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::A
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.

◆ A_old

template<int nVars, int nEqCon, int nIneqCon>
RtVectorX<nIneqCon + nEqCon>::i eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::A_old
private

Definition at line 206 of file eiquadprog-rt.hpp.

◆ chol_

template<int nVars, int nEqCon, int nIneqCon>
Eigen::LLT<typename RtMatrixX<nVars, nVars>::d, Eigen::Lower> eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::chol_
private

current value of cost function

Definition at line 162 of file eiquadprog-rt.hpp.

◆ d

template<int nVars, int nEqCon, int nIneqCon>
RtVectorX<nVars>::d eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::d
private

J' np.

Definition at line 182 of file eiquadprog-rt.hpp.

◆ f_value

template<int nVars, int nEqCon, int nIneqCon>
double eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::f_value
private

max number of active-set iterations

Definition at line 160 of file eiquadprog-rt.hpp.

◆ iaexcl

template<int nVars, int nEqCon, int nIneqCon>
RtVectorX<nIneqCon>::i eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::iaexcl
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.

◆ iai

template<int nVars, int nEqCon, int nIneqCon>
RtVectorX<nIneqCon>::i eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::iai
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.

◆ is_inverse_provided_

template<int nVars, int nEqCon, int nIneqCon>
bool eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::is_inverse_provided_

Definition at line 156 of file eiquadprog-rt.hpp.

◆ iter

template<int nVars, int nEqCon, int nIneqCon>
int eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::iter
private

number of active-set iterations

Definition at line 217 of file eiquadprog-rt.hpp.

◆ m_J

template<int nVars, int nEqCon, int nIneqCon>
RtMatrixX<nVars, nVars>::d eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::m_J

Definition at line 155 of file eiquadprog-rt.hpp.

◆ m_maxIter

template<int nVars, int nEqCon, int nIneqCon>
int eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::m_maxIter
private

Definition at line 159 of file eiquadprog-rt.hpp.

◆ np

template<int nVars, int nEqCon, int nIneqCon>
RtVectorX<nVars>::d eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::np
private

current constraint normal

Definition at line 185 of file eiquadprog-rt.hpp.

◆ q

template<int nVars, int nEqCon, int nIneqCon>
int eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::q
private

size of the active set A (containing the indices of the active constraints)

Definition at line 214 of file eiquadprog-rt.hpp.

◆ R

template<int nVars, int nEqCon, int nIneqCon>
RtMatrixX<nVars, nVars>::d eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::R
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.

◆ r

template<int nVars, int nEqCon, int nIneqCon>
RtVectorX<nIneqCon + nEqCon>::d eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::r
private

infeasibility multipliers, i.e. negative step direction in dual space

Definition at line 173 of file eiquadprog-rt.hpp.

◆ s

template<int nVars, int nEqCon, int nIneqCon>
RtVectorX<nIneqCon>::d eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::s
private

CI*x+ci0.

Definition at line 170 of file eiquadprog-rt.hpp.

◆ solver_return_

template<int nVars, int nEqCon, int nIneqCon>
double eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::solver_return_
private

Definition at line 163 of file eiquadprog-rt.hpp.

◆ u

template<int nVars, int nEqCon, int nIneqCon>
RtVectorX<nIneqCon + nEqCon>::d eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::u
private

Lagrange multipliers.

Definition at line 176 of file eiquadprog-rt.hpp.

◆ u_old

template<int nVars, int nEqCon, int nIneqCon>
RtVectorX<nIneqCon + nEqCon>::d eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::u_old
private

Definition at line 205 of file eiquadprog-rt.hpp.

◆ x_old

template<int nVars, int nEqCon, int nIneqCon>
RtVectorX<nVars>::d eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::x_old
private

Definition at line 204 of file eiquadprog-rt.hpp.

◆ z

template<int nVars, int nEqCon, int nIneqCon>
RtVectorX<nVars>::d eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, nIneqCon >::z
private

step direction in primal space

Definition at line 179 of file eiquadprog-rt.hpp.


The documentation for this class was generated from the following file:


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