Public Types | Public Member Functions | Protected Member Functions | Private Attributes | List of all members
corbo::SolverOsqp Class Reference

Interface to the external solver OSQP. More...

#include <qp_solver_osqp.h>

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

Public Types

using Ptr = std::shared_ptr< SolverOsqp >
 
using UPtr = std::unique_ptr< SolverOsqp >
 
- Public Types inherited from corbo::QpSolverInterface
using Ptr = std::shared_ptr< QpSolverInterface >
 
using SparseMatrix = Eigen::SparseMatrix< double, Eigen::ColMajor, long long >
 
using UPtr = std::unique_ptr< QpSolverInterface >
 

Public Member Functions

void clear () override
 clear internal caches More...
 
void enforceNewStructure (bool new_structure=true) override
 
Eigen::Ref< Eigen::VectorXd > getDualSolution () override
 
QpSolverInterface::Ptr getInstance () const override
 Return a newly created instance of the current solver. More...
 
Eigen::Ref< Eigen::VectorXd > getPrimalSolution () override
 
bool isSupportingSimpleBounds () override
 
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) override
 Solve full QP. More...
 
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) override
 Solve QP without simple bounds. More...
 
void updateDualSolutionWarmStart (const Eigen::Ref< const Eigen::VectorXd > &y) override
 
void updatePrimalSolutionWarmStart (const Eigen::Ref< const Eigen::VectorXd > &x) override
 
- Public Member Functions inherited from corbo::QpSolverInterface
virtual bool initialize ()
 Initialize the qp solver. More...
 
virtual ~QpSolverInterface ()=default
 Virtual destructor. More...
 

Protected Member Functions

void printWarning () const
 

Private Attributes

Eigen::VectorXd _dummy
 

Detailed Description

Interface to the external solver OSQP.

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 134 of file qp_solver_osqp.h.

Member Typedef Documentation

◆ Ptr

using corbo::SolverOsqp::Ptr = std::shared_ptr<SolverOsqp>

Definition at line 137 of file qp_solver_osqp.h.

◆ UPtr

using corbo::SolverOsqp::UPtr = std::unique_ptr<SolverOsqp>

Definition at line 138 of file qp_solver_osqp.h.

Member Function Documentation

◆ clear()

void corbo::SolverOsqp::clear ( )
inlineoverridevirtual

clear internal caches

Implements corbo::QpSolverInterface.

Definition at line 172 of file qp_solver_osqp.h.

◆ enforceNewStructure()

void corbo::SolverOsqp::enforceNewStructure ( bool  new_structure = true)
inlineoverridevirtual

Implements corbo::QpSolverInterface.

Definition at line 170 of file qp_solver_osqp.h.

◆ getDualSolution()

Eigen::Ref<Eigen::VectorXd> corbo::SolverOsqp::getDualSolution ( )
inlineoverridevirtual

Implements corbo::QpSolverInterface.

Definition at line 165 of file qp_solver_osqp.h.

◆ getInstance()

QpSolverInterface::Ptr corbo::SolverOsqp::getInstance ( ) const
inlineoverridevirtual

Return a newly created instance of the current solver.

Implements corbo::QpSolverInterface.

Definition at line 141 of file qp_solver_osqp.h.

◆ getPrimalSolution()

Eigen::Ref<Eigen::VectorXd> corbo::SolverOsqp::getPrimalSolution ( )
inlineoverridevirtual

Implements corbo::QpSolverInterface.

Definition at line 164 of file qp_solver_osqp.h.

◆ isSupportingSimpleBounds()

bool corbo::SolverOsqp::isSupportingSimpleBounds ( )
inlineoverridevirtual

Implements corbo::QpSolverInterface.

Definition at line 144 of file qp_solver_osqp.h.

◆ printWarning()

void corbo::SolverOsqp::printWarning ( ) const
inlineprotected

Definition at line 186 of file qp_solver_osqp.h.

◆ solve() [1/2]

SolverStatus corbo::SolverOsqp::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 
)
inlineoverridevirtual

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

Implements corbo::QpSolverInterface.

Definition at line 147 of file qp_solver_osqp.h.

◆ solve() [2/2]

SolverStatus corbo::SolverOsqp::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 
)
inlineoverridevirtual

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

Implements corbo::QpSolverInterface.

Definition at line 156 of file qp_solver_osqp.h.

◆ updateDualSolutionWarmStart()

void corbo::SolverOsqp::updateDualSolutionWarmStart ( const Eigen::Ref< const Eigen::VectorXd > &  y)
inlineoverridevirtual

Implements corbo::QpSolverInterface.

Definition at line 168 of file qp_solver_osqp.h.

◆ updatePrimalSolutionWarmStart()

void corbo::SolverOsqp::updatePrimalSolutionWarmStart ( const Eigen::Ref< const Eigen::VectorXd > &  x)
inlineoverridevirtual

Implements corbo::QpSolverInterface.

Definition at line 167 of file qp_solver_osqp.h.

Member Data Documentation

◆ _dummy

Eigen::VectorXd corbo::SolverOsqp::_dummy
private

Definition at line 189 of file qp_solver_osqp.h.


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