Public Member Functions | Protected Member Functions | Protected Attributes | List of all members

Abstract base class for algorithms solving quadratic programs. More...

#include <dense_qp_solver.hpp>

Inheritance diagram for DenseQPsolver:
Inheritance graph
[legend]

Public Member Functions

virtual DenseCPsolverclone () const =0
 
virtual DenseQPsolvercloneDenseQPsolver () const =0
 
 DenseQPsolver ()
 
 DenseQPsolver (UserInteraction *_userInteraction)
 
 DenseQPsolver (const DenseQPsolver &rhs)
 
virtual returnValue getDualSolution (DVector &yOpt) const =0
 
virtual uint getNumberOfConstraints () const =0
 
virtual uint getNumberOfIterations () const
 
virtual uint getNumberOfVariables () const =0
 
virtual double getObjVal () const =0
 
virtual returnValue getPrimalSolution (DVector &xOpt) const =0
 
QPStatus getStatus () const
 
virtual returnValue getVarianceCovariance (DMatrix &var)=0
 
virtual returnValue getVarianceCovariance (DMatrix &H, DMatrix &var)=0
 
virtual returnValue init (const DenseCP *cp)
 
virtual returnValue init (uint nV, uint nC)
 
BooleanType isInfeasible () const
 
BooleanType isSolved () const
 
BooleanType isUnbounded () const
 
DenseQPsolveroperator= (const DenseQPsolver &rhs)
 
virtual returnValue solve (DenseCP *cp_)
 
virtual returnValue solve (double *H, double *A, double *g, double *lb, double *ub, double *lbA, double *ubA, uint maxIter)=0
 
virtual returnValue solve (DMatrix *H, DMatrix *A, DVector *g, DVector *lb, DVector *ub, DVector *lbA, DVector *ubA, uint maxIter)=0
 
virtual returnValue step (double *H, double *A, double *g, double *lb, double *ub, double *lbA, double *ubA)=0
 
virtual returnValue step (DMatrix *H, DMatrix *A, DVector *g, DVector *lb, DVector *ub, DVector *lbA, DVector *ubA)=0
 
 ~DenseQPsolver ()
 
- Public Member Functions inherited from DenseCPsolver
 DenseCPsolver ()
 
 DenseCPsolver (UserInteraction *_userInteraction)
 
 DenseCPsolver (const DenseCPsolver &rhs)
 
DenseCPsolveroperator= (const DenseCPsolver &rhs)
 
virtual ~DenseCPsolver ()
 
- Public Member Functions inherited from AlgorithmicBase
int addLogRecord (LogRecord &_record)
 
returnValue addOption (OptionsName name, int value)
 
returnValue addOption (OptionsName name, double value)
 
returnValue addOption (uint idx, OptionsName name, int value)
 
returnValue addOption (uint idx, OptionsName name, double value)
 
returnValue addOptionsList ()
 
 AlgorithmicBase ()
 
 AlgorithmicBase (UserInteraction *_userInteraction)
 
 AlgorithmicBase (const AlgorithmicBase &rhs)
 
returnValue get (OptionsName name, int &value) const
 
returnValue get (OptionsName name, double &value) const
 
returnValue get (OptionsName name, std::string &value) const
 
returnValue get (uint idx, OptionsName name, int &value) const
 
returnValue get (uint idx, OptionsName name, double &value) const
 
returnValue getAll (LogName _name, MatrixVariablesGrid &values) const
 
returnValue getFirst (LogName _name, DMatrix &firstValue) const
 
returnValue getFirst (LogName _name, VariablesGrid &firstValue) const
 
returnValue getLast (LogName _name, DMatrix &lastValue) const
 
returnValue getLast (LogName _name, VariablesGrid &lastValue) const
 
Options getOptions (uint idx) const
 
BooleanType haveOptionsChanged () const
 
BooleanType haveOptionsChanged (uint idx) const
 
AlgorithmicBaseoperator= (const AlgorithmicBase &rhs)
 
returnValue plot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
 
returnValue printLogRecord (std::ostream &_stream, int idx, LogPrintMode _mode=PRINT_ITEM_BY_ITEM) const
 
returnValue replot (PlotFrequency _frequency=PLOT_IN_ANY_CASE)
 
returnValue set (OptionsName name, int value)
 
returnValue set (OptionsName name, double value)
 
returnValue set (OptionsName name, const std::string &value)
 
returnValue set (uint idx, OptionsName name, int value)
 
returnValue set (uint idx, OptionsName name, double value)
 
returnValue setAll (LogName _name, const MatrixVariablesGrid &values)
 
returnValue setLast (LogName _name, int lastValue, double time=-INFTY)
 
returnValue setLast (LogName _name, double lastValue, double time=-INFTY)
 
returnValue setLast (LogName _name, const DVector &lastValue, double time=-INFTY)
 
returnValue setLast (LogName _name, const DMatrix &lastValue, double time=-INFTY)
 
returnValue setLast (LogName _name, const VariablesGrid &lastValue, double time=-INFTY)
 
returnValue setOptions (const Options &arg)
 
returnValue setOptions (uint idx, const Options &arg)
 
virtual ~AlgorithmicBase ()
 

Protected Member Functions

virtual returnValue makeBoundsConsistent (DenseCP *cp) const
 
virtual returnValue setupLogging ()
 
virtual returnValue setupQPobject (uint nV, uint nC)=0
 
- Protected Member Functions inherited from DenseCPsolver
virtual returnValue setupOptions ()
 

Protected Attributes

int numberOfSteps
 
QPStatus qpStatus
 
- Protected Attributes inherited from AlgorithmicBase
int outputLoggingIdx
 
BooleanType useModuleStandalone
 
UserInteractionuserInteraction
 

Detailed Description

Abstract base class for algorithms solving quadratic programs.

The class DenseQPsolver provides an abstract base class for different algorithms for solving quadratic programming (QP) problems.

\author Boris Houska, Hans Joachim Ferreau

Definition at line 57 of file dense_qp_solver.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO DenseQPsolver::DenseQPsolver ( )

Default constructor.

Definition at line 44 of file dense_qp_solver.cpp.

DenseQPsolver::DenseQPsolver ( UserInteraction _userInteraction)

Definition at line 53 of file dense_qp_solver.cpp.

DenseQPsolver::DenseQPsolver ( const DenseQPsolver rhs)

Copy constructor (deep copy).

Definition at line 62 of file dense_qp_solver.cpp.

DenseQPsolver::~DenseQPsolver ( )

Destructor.

Definition at line 69 of file dense_qp_solver.cpp.

Member Function Documentation

virtual DenseCPsolver* DenseQPsolver::clone ( ) const
pure virtual

Implements DenseCPsolver.

Implemented in QPsolver_qpOASES.

virtual DenseQPsolver* DenseQPsolver::cloneDenseQPsolver ( ) const
pure virtual

Implemented in QPsolver_qpOASES.

virtual returnValue DenseQPsolver::getDualSolution ( DVector yOpt) const
pure virtual

Returns dual solution vector if QP has been solved.

Returns
SUCCESSFUL_RETURN
RET_QP_NOT_SOLVED
Parameters
yOptOUTPUT: dual solution vector.

Implemented in QPsolver_qpOASES.

virtual uint DenseQPsolver::getNumberOfConstraints ( ) const
pure virtual

Implemented in QPsolver_qpOASES.

uint DenseQPsolver::getNumberOfIterations ( ) const
virtual

Returns number of iterations performed at last QP solution.

Returns
Number of iterations performed at last QP solution

Implements DenseCPsolver.

Definition at line 141 of file dense_qp_solver.cpp.

virtual uint DenseQPsolver::getNumberOfVariables ( ) const
pure virtual

Implemented in QPsolver_qpOASES.

virtual double DenseQPsolver::getObjVal ( ) const
pure virtual

Returns optimal objective function value.

Returns
finite value: Optimal objective function value (QP has been solved)
+INFTY: QP has not been solved or is infeasible
-INFTY: QP is unbounded

Implemented in QPsolver_qpOASES.

virtual returnValue DenseQPsolver::getPrimalSolution ( DVector xOpt) const
pure virtual

Returns primal solution vector if QP has been solved.

Returns
SUCCESSFUL_RETURN
RET_QP_NOT_SOLVED
Parameters
xOptOUTPUT: primal solution vector.

Implemented in QPsolver_qpOASES.

QPStatus DenseQPsolver::getStatus ( ) const
inline

Returns QP status.

Returns
QP status
virtual returnValue DenseQPsolver::getVarianceCovariance ( DMatrix var)
pure virtual

Returns a variance-covariance estimate if possible or an error message otherwise.

Returns
SUCCESSFUL_RETURN RET_MEMBER_NOT_INITIALISED

Implements DenseCPsolver.

Implemented in QPsolver_qpOASES.

virtual returnValue DenseQPsolver::getVarianceCovariance ( DMatrix H,
DMatrix var 
)
pure virtual

Returns a variance-covariance estimate if possible or an error message otherwise.

Returns
SUCCESSFUL_RETURN RET_MEMBER_NOT_INITIALISED

Implements DenseCPsolver.

Implemented in QPsolver_qpOASES.

returnValue DenseQPsolver::init ( const DenseCP cp)
virtual

Initializes QP object.

Returns
SUCCESSFUL_RETURN

Implements DenseCPsolver.

Definition at line 93 of file dense_qp_solver.cpp.

returnValue DenseQPsolver::init ( uint  nV,
uint  nC 
)
virtual

Alternative way to initialize QP object.

Parameters
nVNumber of QP variables.
nCNumber of QP constraints (without bounds).

Definition at line 86 of file dense_qp_solver.cpp.

BooleanType DenseQPsolver::isInfeasible ( ) const
inline

Returns if QP has been found to be infeasible.

Returns
BT_TRUE if QP is infeasible
BooleanType DenseQPsolver::isSolved ( ) const
inline

Returns if QP (or its relaxation) has been solved.

Returns
BT_TRUE iff QP has been solved
BooleanType DenseQPsolver::isUnbounded ( ) const
inline

Returns if QP has been found to be unbounded.

Returns
BT_TRUE if QP is unbounded
returnValue DenseQPsolver::makeBoundsConsistent ( DenseCP cp) const
protectedvirtual

Definition at line 168 of file dense_qp_solver.cpp.

DenseQPsolver & DenseQPsolver::operator= ( const DenseQPsolver rhs)

Assignment operator (deep copy).

Definition at line 74 of file dense_qp_solver.cpp.

returnValue DenseQPsolver::setupLogging ( )
protectedvirtual

Reimplemented from DenseCPsolver.

Definition at line 154 of file dense_qp_solver.cpp.

virtual returnValue DenseQPsolver::setupQPobject ( uint  nV,
uint  nC 
)
protectedpure virtual

Setups QP object.

Returns
SUCCESSFUL_RETURN
RET_QP_INIT_FAILED
Parameters
nVNumber of QP variables.
nCNumber of QP constraints (without bounds).

Implemented in QPsolver_qpOASES.

returnValue DenseQPsolver::solve ( DenseCP cp_)
virtual

Solves the QP.

Implements DenseCPsolver.

Reimplemented in QPsolver_qpOASES.

Definition at line 104 of file dense_qp_solver.cpp.

virtual returnValue DenseQPsolver::solve ( double *  H,
double *  A,
double *  g,
double *  lb,
double *  ub,
double *  lbA,
double *  ubA,
uint  maxIter 
)
pure virtual

Solves QP using at most <maxIter> iterations.

Parameters
HHessian matrix of neighbouring QP to be solved.
AConstraint matrix of neighbouring QP to be solved.
gGradient of neighbouring QP to be solved.
lbLower bounds of neighbouring QP to be solved.
ubUpper bounds of neighbouring QP to be solved.
lbALower constraints' bounds of neighbouring QP to be solved.
ubAUpper constraints' bounds of neighbouring QP to be solved.
maxIterMaximum number of iterations.

Implemented in QPsolver_qpOASES.

virtual returnValue DenseQPsolver::solve ( DMatrix H,
DMatrix A,
DVector g,
DVector lb,
DVector ub,
DVector lbA,
DVector ubA,
uint  maxIter 
)
pure virtual

Solves QP using at most <maxIter> iterations.

Parameters
HHessian matrix of neighbouring QP to be solved.
AConstraint matrix of neighbouring QP to be solved.
gGradient of neighbouring QP to be solved.
lbLower bounds of neighbouring QP to be solved.
ubUpper bounds of neighbouring QP to be solved.
lbALower constraints' bounds of neighbouring QP to be solved.
ubAUpper constraints' bounds of neighbouring QP to be solved.
maxIterMaximum number of iterations.

Implemented in QPsolver_qpOASES.

virtual returnValue DenseQPsolver::step ( double *  H,
double *  A,
double *  g,
double *  lb,
double *  ub,
double *  lbA,
double *  ubA 
)
pure virtual

Performs exactly one QP iteration.

Parameters
HHessian matrix of neighbouring QP to be solved.
AConstraint matrix of neighbouring QP to be solved.
gGradient of neighbouring QP to be solved.
lbLower bounds of neighbouring QP to be solved.
ubUpper bounds of neighbouring QP to be solved.
lbALower constraints' bounds of neighbouring QP to be solved.
ubAUpper constraints' bounds of neighbouring QP to be solved.

Implemented in QPsolver_qpOASES.

virtual returnValue DenseQPsolver::step ( DMatrix H,
DMatrix A,
DVector g,
DVector lb,
DVector ub,
DVector lbA,
DVector ubA 
)
pure virtual

Performs exactly one QP iteration.

Parameters
HHessian matrix of neighbouring QP to be solved.
AConstraint matrix of neighbouring QP to be solved.
gGradient of neighbouring QP to be solved.
lbLower bounds of neighbouring QP to be solved.
ubUpper bounds of neighbouring QP to be solved.
lbALower constraints' bounds of neighbouring QP to be solved.
ubAUpper constraints' bounds of neighbouring QP to be solved.

Implemented in QPsolver_qpOASES.

Member Data Documentation

int DenseQPsolver::numberOfSteps
protected

Definition at line 236 of file dense_qp_solver.hpp.

QPStatus DenseQPsolver::qpStatus
protected

Definition at line 235 of file dense_qp_solver.hpp.


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


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Mon Jun 10 2019 12:35:23