qp_solver_collection
|
Virtual class of QP solver. More...
#include <QpSolverCollection.h>
Public Types | |
using | clock = typename std::conditional< std::chrono::high_resolution_clock::is_steady, std::chrono::high_resolution_clock, std::chrono::steady_clock >::type |
Public Member Functions | |
QpSolver () | |
Constructor. More... | |
void | printInfo (bool verbose=false, const std::string &header="") const |
Print information. More... | |
virtual Eigen::VectorXd | solve (int dim_var, int dim_eq, int dim_ineq, Eigen::Ref< Eigen::MatrixXd > Q, const Eigen::Ref< const Eigen::VectorXd > &c, const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::VectorXd > &b, const Eigen::Ref< const Eigen::MatrixXd > &C, const Eigen::Ref< const Eigen::VectorXd > &d, const Eigen::Ref< const Eigen::VectorXd > &x_min, const Eigen::Ref< const Eigen::VectorXd > &x_max)=0 |
Solve QP. More... | |
virtual Eigen::VectorXd | solve (QpCoeff &qp_coeff) |
Solve QP. More... | |
QpSolverType | type () const |
Get QP solver type. More... | |
bool | solveFailed () const |
Get whether it failed to solve the QP. More... | |
Protected Attributes | |
QpSolverType | type_ = QpSolverType::Uninitialized |
QP solver type. More... | |
bool | solve_failed_ = false |
Whether it failed to solve the QP. More... | |
Virtual class of QP solver.
Definition at line 192 of file QpSolverCollection.h.
using QpSolverCollection::QpSolver::clock = typename std::conditional<std::chrono::high_resolution_clock::is_steady, std::chrono::high_resolution_clock, std::chrono::steady_clock>::type |
Definition at line 197 of file QpSolverCollection.h.
|
inline |
Constructor.
Definition at line 201 of file QpSolverCollection.h.
void QpSolverCollection::QpSolver::printInfo | ( | bool | verbose = false , |
const std::string & | header = "" |
||
) | const |
Print information.
|
pure virtual |
Solve QP.
dim_var | dimension of decision variable |
dim_eq | dimension of equality constraint |
dim_ineq | dimension of inequality constraint |
Q | objective matrix (LSSOL requires non-const for Q) |
c | objective vector |
A | equality constraint matrix |
b | equality constraint vector |
C | inequality constraint matrix |
d | inequality constraint vector |
x_min | lower bound |
x_max | upper bound |
QP is formulated as follows:
\begin{align*} & min_{\boldsymbol{x}} \ \frac{1}{2}{\boldsymbol{x}^T \boldsymbol{Q} \boldsymbol{x}} + {\boldsymbol{c}^T \boldsymbol{x}} \\ & s.t. \ \ \boldsymbol{A} \boldsymbol{x} = \boldsymbol{b} \nonumber \\ & \phantom{s.t.} \ \ \boldsymbol{C} \boldsymbol{x} \leq \boldsymbol{d} \nonumber \\ & \phantom{s.t.} \ \ \boldsymbol{x}_{min} \leq \boldsymbol{x} \leq \boldsymbol{x}_{max} \nonumber \end{align*}
Implemented in QpSolverCollection::QpSolverQpmad, QpSolverCollection::QpSolverProxqp, QpSolverCollection::QpSolverHpipm, QpSolverCollection::QpSolverNasoq, QpSolverCollection::QpSolverOsqp, QpSolverCollection::QpSolverQpoases, QpSolverCollection::QpSolverJrlqp, QpSolverCollection::QpSolverLssol, QpSolverCollection::QpSolverQuadprog, and QpSolverCollection::QpSolverQld.
|
virtual |
Solve QP.
qp_coeff | QP coefficient |
|
inline |
Get whether it failed to solve the QP.
Definition at line 256 of file QpSolverCollection.h.
|
inline |
Get QP solver type.
Definition at line 250 of file QpSolverCollection.h.
|
protected |
Whether it failed to solve the QP.
Definition at line 266 of file QpSolverCollection.h.
|
protected |
QP solver type.
Definition at line 263 of file QpSolverCollection.h.