#include <solver-proxqp.hpp>
Public Types | |
typedef math::ConstRefMatrix | ConstRefMatrix |
typedef math::ConstRefVector | ConstRefVector |
typedef math::RefVector | RefVector |
typedef math::Vector | Vector |
![]() | |
typedef math::ConstRefMatrix | ConstRefMatrix |
typedef math::ConstRefVector | ConstRefVector |
typedef math::RefVector | RefVector |
Public Member Functions | |
double | getObjectiveValue () override |
const QPData | getQPData () const |
void | resize (unsigned int n, unsigned int neq, unsigned int nin) override |
void | retrieveQPData (const HQPData &problemData, const bool hessianRegularization=false) override |
void | setEpsilonAbsolute (double epsAbs) |
void | setEpsilonRelative (double epsRel) |
bool | setMaximumIterations (unsigned int maxIter) override |
void | setMuEquality (double muEq) |
void | setMuInequality (double muIn) |
void | setRho (double rho) |
void | setVerbose (bool isVerbose=false) |
const HQPOutput & | solve (const HQPData &problemData) override |
SolverProxQP (const std::string &name) | |
![]() | |
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 | |
double | m_epsAbs |
double | m_epsRel |
double | m_hessian_regularization |
bool | m_isVerbose |
double | m_muEq |
double | m_muIn |
unsigned int | m_n |
number of inequality constraints More... | |
unsigned int | m_neq |
unsigned int | m_nin |
number of equality constraints More... | |
double | m_objValue |
QPDataTpl< double > | m_qpData |
number of variables More... | |
double | m_rho |
dense::QP< double > | m_solver |
![]() | |
unsigned int | m_maxIter |
double | m_maxTime |
std::string | m_name |
HQPOutput | m_output |
bool | m_useWarmStart |
Additional Inherited Members | |
![]() | |
static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const std::string | HQP_status_string [5] |
Definition at line 42 of file solvers/solver-proxqp.hpp.
typedef math::ConstRefMatrix tsid::solvers::SolverProxQP::ConstRefMatrix |
Definition at line 50 of file solvers/solver-proxqp.hpp.
typedef math::ConstRefVector tsid::solvers::SolverProxQP::ConstRefVector |
Definition at line 49 of file solvers/solver-proxqp.hpp.
Definition at line 48 of file solvers/solver-proxqp.hpp.
Definition at line 47 of file solvers/solver-proxqp.hpp.
tsid::solvers::SolverProxQP::SolverProxQP | ( | const std::string & | name | ) |
Definition at line 26 of file solver-proxqp.cpp.
|
overridevirtual |
Get the objective value of the last solved problem.
Implements tsid::solvers::SolverHQPBase.
Definition at line 243 of file solver-proxqp.cpp.
|
inline |
Return the QP data object.
Definition at line 61 of file solvers/solver-proxqp.hpp.
|
overridevirtual |
Implements tsid::solvers::SolverHQPBase.
Definition at line 46 of file solver-proxqp.cpp.
|
overridevirtual |
Retrieve the matrices describing a QP problem from the problem data.
Implements tsid::solvers::SolverHQPBase.
Definition at line 96 of file solver-proxqp.cpp.
|
protected |
Definition at line 42 of file solver-proxqp.cpp.
void tsid::solvers::SolverProxQP::setEpsilonAbsolute | ( | double | epsAbs | ) |
Definition at line 265 of file solver-proxqp.cpp.
void tsid::solvers::SolverProxQP::setEpsilonRelative | ( | double | epsRel | ) |
Definition at line 269 of file solver-proxqp.cpp.
|
overridevirtual |
Set the current maximum number of iterations performed by the solver.
Reimplemented from tsid::solvers::SolverHQPBase.
Definition at line 247 of file solver-proxqp.cpp.
void tsid::solvers::SolverProxQP::setMuEquality | ( | double | muEq | ) |
Definition at line 257 of file solver-proxqp.cpp.
void tsid::solvers::SolverProxQP::setMuInequality | ( | double | muIn | ) |
Definition at line 253 of file solver-proxqp.cpp.
void tsid::solvers::SolverProxQP::setRho | ( | double | rho | ) |
Definition at line 261 of file solver-proxqp.cpp.
void tsid::solvers::SolverProxQP::setVerbose | ( | bool | isVerbose = false | ) |
Definition at line 273 of file solver-proxqp.cpp.
Solve the given Hierarchical Quadratic Program
Implements tsid::solvers::SolverHQPBase.
Definition at line 177 of file solver-proxqp.cpp.
|
protected |
Definition at line 97 of file solvers/solver-proxqp.hpp.
|
protected |
Definition at line 98 of file solvers/solver-proxqp.hpp.
|
protected |
Definition at line 84 of file solvers/solver-proxqp.hpp.
|
protected |
Definition at line 99 of file solvers/solver-proxqp.hpp.
|
protected |
Definition at line 96 of file solvers/solver-proxqp.hpp.
|
protected |
Definition at line 95 of file solvers/solver-proxqp.hpp.
|
protected |
number of inequality constraints
Definition at line 90 of file solvers/solver-proxqp.hpp.
|
protected |
Definition at line 88 of file solvers/solver-proxqp.hpp.
|
protected |
number of equality constraints
Definition at line 89 of file solvers/solver-proxqp.hpp.
|
protected |
Definition at line 83 of file solvers/solver-proxqp.hpp.
|
protected |
number of variables
Definition at line 92 of file solvers/solver-proxqp.hpp.
|
protected |
Definition at line 94 of file solvers/solver-proxqp.hpp.
|
protected |
Definition at line 86 of file solvers/solver-proxqp.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Matrix tsid::solvers::SolverProxQP::Matrix |
Definition at line 46 of file solvers/solver-proxqp.hpp.