Public Types | Public Member Functions | List of all members
corbo::QpSolverInterface Class Referenceabstract

Generic interface for QP solver implementations. More...

#include <qp_solver_interface.h>

Inheritance diagram for corbo::QpSolverInterface:
Inheritance graph
[legend]

Public Types

using Ptr = std::shared_ptr< QpSolverInterface >
 
using SparseMatrix = Eigen::SparseMatrix< double, Eigen::ColMajor, long long >
 
using UPtr = std::unique_ptr< QpSolverInterface >
 

Public Member Functions

virtual void clear ()=0
 clear internal caches More...
 
virtual void enforceNewStructure (bool new_structure=true)=0
 
virtual Eigen::Ref< Eigen::VectorXd > getDualSolution ()=0
 
virtual Ptr getInstance () const =0
 Return a newly created instance of the current solver. More...
 
virtual Eigen::Ref< Eigen::VectorXd > getPrimalSolution ()=0
 
virtual bool initialize ()
 Initialize the qp solver. More...
 
virtual bool isSupportingSimpleBounds ()=0
 
virtual SolverStatus solve (SparseMatrix &P, Eigen::Ref< Eigen::VectorXd > q, SparseMatrix &A, Eigen::Ref< Eigen::VectorXd > lbA, Eigen::Ref< Eigen::VectorXd > ubA, Eigen::Ref< Eigen::VectorXd > lb, Eigen::Ref< Eigen::VectorXd > ub, bool new_structure=true, bool zero_x_warmstart=false)=0
 Solve full QP. More...
 
virtual SolverStatus solve (SparseMatrix &P, Eigen::Ref< Eigen::VectorXd > q, SparseMatrix &A, Eigen::Ref< Eigen::VectorXd > lbA, Eigen::Ref< Eigen::VectorXd > ubA, bool new_structure=true, bool zero_x_warmstart=false, bool update_P=true, bool update_q=true, bool update_A=true, bool update_bounds=true)=0
 Solve QP without simple bounds. More...
 
virtual void updateDualSolutionWarmStart (const Eigen::Ref< const Eigen::VectorXd > &y)=0
 
virtual void updatePrimalSolutionWarmStart (const Eigen::Ref< const Eigen::VectorXd > &x)=0
 
virtual ~QpSolverInterface ()=default
 Virtual destructor. More...
 

Detailed Description

Generic interface for QP solver implementations.

This class can be used to generically define solver back-ends for optimization problems with quadratic objectives and linear constraints.

Since we are currently working with OSQP, the interface is primarly defined to perfectly match the OSQP interface. This means we require SparseMatrix indices vectors to be defined in long long format. Furthermore, the problem definition is as follows

\[ \min 0.5 x^T P x + q^T x \\ \text{subject to:} \\ lbA <= A x <= ubB \\ lb <= x <= ub \]

The gradient of the Lagrangian is defined as follows: grad L(x, lambda, mu) = grad f(x) + A^T lambda + mu

Some QP solvers do not allow the special treatment of bounds. The particular solver implementation creates a new matrix Atile = [A; I] for that purpose. However, in order to avoid this step, isSupportingSimpleBounds() can be checked a-priori.

Note, bounds can be set to corbo_DBL_INF and -corbo_DBL_INF respectively.

See also
OptimizationProblemInterface
Author
Christoph Rösmann (chris.nosp@m.toph.nosp@m..roes.nosp@m.mann.nosp@m.@tu-d.nosp@m.ortm.nosp@m.und.d.nosp@m.e)

Definition at line 73 of file qp_solver_interface.h.

Member Typedef Documentation

◆ Ptr

Definition at line 76 of file qp_solver_interface.h.

◆ SparseMatrix

Definition at line 79 of file qp_solver_interface.h.

◆ UPtr

Definition at line 77 of file qp_solver_interface.h.

Constructor & Destructor Documentation

◆ ~QpSolverInterface()

virtual corbo::QpSolverInterface::~QpSolverInterface ( )
virtualdefault

Virtual destructor.

Member Function Documentation

◆ clear()

virtual void corbo::QpSolverInterface::clear ( )
pure virtual

clear internal caches

Implemented in corbo::SolverOsqp.

◆ enforceNewStructure()

virtual void corbo::QpSolverInterface::enforceNewStructure ( bool  new_structure = true)
pure virtual

Implemented in corbo::SolverOsqp.

◆ getDualSolution()

virtual Eigen::Ref<Eigen::VectorXd> corbo::QpSolverInterface::getDualSolution ( )
pure virtual

Implemented in corbo::SolverOsqp.

◆ getInstance()

virtual Ptr corbo::QpSolverInterface::getInstance ( ) const
pure virtual

Return a newly created instance of the current solver.

Implemented in corbo::SolverOsqp.

◆ getPrimalSolution()

virtual Eigen::Ref<Eigen::VectorXd> corbo::QpSolverInterface::getPrimalSolution ( )
pure virtual

Implemented in corbo::SolverOsqp.

◆ initialize()

virtual bool corbo::QpSolverInterface::initialize ( )
inlinevirtual

Initialize the qp solver.

Definition at line 93 of file qp_solver_interface.h.

◆ isSupportingSimpleBounds()

virtual bool corbo::QpSolverInterface::isSupportingSimpleBounds ( )
pure virtual

Implemented in corbo::SolverOsqp.

◆ solve() [1/2]

virtual SolverStatus corbo::QpSolverInterface::solve ( SparseMatrix P,
Eigen::Ref< Eigen::VectorXd >  q,
SparseMatrix A,
Eigen::Ref< Eigen::VectorXd >  lbA,
Eigen::Ref< Eigen::VectorXd >  ubA,
Eigen::Ref< Eigen::VectorXd >  lb,
Eigen::Ref< Eigen::VectorXd >  ub,
bool  new_structure = true,
bool  zero_x_warmstart = false 
)
pure virtual

Solve full QP.

Remarks
We require that all arguments are non-const in order to facilitate the usage of some lowlevel c-APIs (e.g. OSQP).
Parameters
[in]PQuadratic form matrix,
[in]qLinear part
[in]ALinear constraint matrix
[in]lbALower bounds of linear constraints
[in]ubAUpper bounds of linear constraints
[in]lbLower bounds of parameters
[in]ubUpper bounds of parameters
[in]new_structureIf true, the solver must reallocte the internal memory
Returns
Solver status

Implemented in corbo::SolverOsqp.

◆ solve() [2/2]

virtual SolverStatus corbo::QpSolverInterface::solve ( SparseMatrix P,
Eigen::Ref< Eigen::VectorXd >  q,
SparseMatrix A,
Eigen::Ref< Eigen::VectorXd >  lbA,
Eigen::Ref< Eigen::VectorXd >  ubA,
bool  new_structure = true,
bool  zero_x_warmstart = false,
bool  update_P = true,
bool  update_q = true,
bool  update_A = true,
bool  update_bounds = true 
)
pure virtual

Solve QP without simple bounds.

Remarks
We require that all arguments are non-const in order to facilitate the usage of some lowlevel c-APIs (e.g. OSQP).
Parameters
[in]PQuadratic form matrix,
[in]qLinear part
[in]ALinear constraint matrix
[in]lbALower bounds of linear constraints
[in]ubAUpper bounds of linear constraints
[in]new_structureIf true, the solver must reallocte the internal memory
Returns
Solver status

Implemented in corbo::SolverOsqp.

◆ updateDualSolutionWarmStart()

virtual void corbo::QpSolverInterface::updateDualSolutionWarmStart ( const Eigen::Ref< const Eigen::VectorXd > &  y)
pure virtual

Implemented in corbo::SolverOsqp.

◆ updatePrimalSolutionWarmStart()

virtual void corbo::QpSolverInterface::updatePrimalSolutionWarmStart ( const Eigen::Ref< const Eigen::VectorXd > &  x)
pure virtual

Implemented in corbo::SolverOsqp.


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


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:08:03