#include <solver-HQP-eiquadprog-rt.hpp>

Public Types | |
| typedef math::ConstRefMatrix | ConstRefMatrix |
| typedef math::ConstRefVector | ConstRefVector |
| typedef math::RefVector | RefVector |
| typedef math::Vector | Vector |
Public Types inherited from tsid::solvers::SolverHQPBase | |
| typedef math::ConstRefMatrix | ConstRefMatrix |
| typedef math::ConstRefVector | ConstRefVector |
| typedef math::RefVector | RefVector |
Public Member Functions | |
| double | getObjectiveValue () override |
| void | resize (unsigned int n, unsigned int neq, unsigned int nin) override |
| void | retrieveQPData (const HQPData &, const bool) override |
| bool | setMaximumIterations (unsigned int maxIter) override |
| const HQPOutput & | solve (const HQPData &problemData) override |
| SolverHQuadProgRT (const std::string &name) | |
Public Member Functions inherited from tsid::solvers::SolverHQPBase | |
| virtual unsigned int | getMaximumIterations () |
| virtual double | getMaximumTime () |
| virtual bool | getUseWarmStart () |
| virtual const std::string & | name () const |
| virtual bool | setMaximumTime (double seconds) |
| virtual void | setUseWarmStart (bool useWarmStart) |
| SolverHQPBase (const std::string &name) | |
| virtual | ~SolverHQPBase ()=default |
Public Attributes | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Matrix | Matrix |
Protected Member Functions | |
| void | sendMsg (const std::string &s) |
Protected Attributes | |
| Eigen::VectorXi | m_activeSet |
| int | m_activeSetSize |
| vector containing the indexes of the active inequalities More... | |
| RtMatrixX< nEqCon, nVars >::d | m_CE |
| RtVectorX< nEqCon >::d | m_ce0 |
| RtMatrixX< 2 *nIneqCon, nVars >::d | m_CI |
| RtVectorX< 2 *nIneqCon >::d | m_ci0 |
| twice the rows because inequality constraints are bilateral More... | |
| RtVectorX< nVars >::d | m_g |
| RtMatrixX< nVars, nVars >::d | m_H |
| double | m_hessian_regularization |
| int | m_n |
| number of inequality constraints More... | |
| int | m_neq |
| int | m_nin |
| number of equality constraints More... | |
| double | m_objValue |
| eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, 2 *nIneqCon > | m_solver |
Protected Attributes inherited from tsid::solvers::SolverHQPBase | |
| unsigned int | m_maxIter |
| double | m_maxTime |
| std::string | m_name |
| HQPOutput | m_output |
| bool | m_useWarmStart |
Additional Inherited Members | |
Static Public Attributes inherited from tsid::solvers::SolverHQPBase | |
| static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const std::string | HQP_status_string [5] |
Definition at line 33 of file solver-HQP-eiquadprog-rt.hpp.
| typedef math::ConstRefMatrix tsid::solvers::SolverHQuadProgRT< nVars, nEqCon, nIneqCon >::ConstRefMatrix |
Definition at line 41 of file solver-HQP-eiquadprog-rt.hpp.
| typedef math::ConstRefVector tsid::solvers::SolverHQuadProgRT< nVars, nEqCon, nIneqCon >::ConstRefVector |
Definition at line 40 of file solver-HQP-eiquadprog-rt.hpp.
| typedef math::RefVector tsid::solvers::SolverHQuadProgRT< nVars, nEqCon, nIneqCon >::RefVector |
Definition at line 39 of file solver-HQP-eiquadprog-rt.hpp.
| typedef math::Vector tsid::solvers::SolverHQuadProgRT< nVars, nEqCon, nIneqCon >::Vector |
Definition at line 38 of file solver-HQP-eiquadprog-rt.hpp.
| tsid::solvers::SolverHQuadProgRT< nVars, nEqCon, nIneqCon >::SolverHQuadProgRT | ( | const std::string & | name | ) |
|
overridevirtual |
Get the objective value of the last solved problem.
Implements tsid::solvers::SolverHQPBase.
|
overridevirtual |
Implements tsid::solvers::SolverHQPBase.
|
inlineoverridevirtual |
Retrieve the matrices describing a QP problem from the problem data.
Implements tsid::solvers::SolverHQPBase.
Definition at line 53 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
|
overridevirtual |
Set the current maximum number of iterations performed by the solver.
Reimplemented from tsid::solvers::SolverHQPBase.
|
overridevirtual |
Solve the given Hierarchical Quadratic Program
Implements tsid::solvers::SolverHQPBase.
|
protected |
Definition at line 82 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
vector containing the indexes of the active inequalities
Definition at line 83 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
Definition at line 72 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
Definition at line 73 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
Definition at line 75 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
twice the rows because inequality constraints are bilateral
Definition at line 76 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
Definition at line 71 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
Definition at line 70 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
Definition at line 79 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
number of inequality constraints
Definition at line 90 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
Definition at line 88 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
number of equality constraints
Definition at line 89 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
Definition at line 77 of file solver-HQP-eiquadprog-rt.hpp.
|
protected |
Definition at line 68 of file solver-HQP-eiquadprog-rt.hpp.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Matrix tsid::solvers::SolverHQuadProgRT< nVars, nEqCon, nIneqCon >::Matrix |
Definition at line 37 of file solver-HQP-eiquadprog-rt.hpp.