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

(not yet documented) More...

#include <qp_solver_qpoases.hpp>

Inheritance diagram for QPsolver_qpOASES:
Inheritance graph
[legend]

Public Member Functions

virtual DenseCPsolverclone () const
 
virtual DenseQPsolvercloneDenseQPsolver () const
 
virtual returnValue getDualSolution (DVector &yOpt) const
 
virtual uint getNumberOfConstraints () const
 
virtual uint getNumberOfVariables () const
 
virtual double getObjVal () const
 
virtual returnValue getPrimalSolution (DVector &xOpt) const
 
virtual returnValue getVarianceCovariance (DMatrix &var)
 
virtual returnValue getVarianceCovariance (DMatrix &H, DMatrix &var)
 
QPsolver_qpOASESoperator= (const QPsolver_qpOASES &rhs)
 
 QPsolver_qpOASES ()
 
 QPsolver_qpOASES (UserInteraction *_userInteraction)
 
 QPsolver_qpOASES (const QPsolver_qpOASES &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)
 
virtual returnValue solve (DMatrix *H, DMatrix *A, DVector *g, DVector *lb, DVector *ub, DVector *lbA, DVector *ubA, uint maxIter)
 
virtual returnValue step (double *H, double *A, double *g, double *lb, double *ub, double *lbA, double *ubA)
 
virtual returnValue step (DMatrix *H, DMatrix *A, DVector *g, DVector *lb, DVector *ub, DVector *lbA, DVector *ubA)
 
virtual ~QPsolver_qpOASES ()
 
- Public Member Functions inherited from DenseQPsolver
 DenseQPsolver ()
 
 DenseQPsolver (UserInteraction *_userInteraction)
 
 DenseQPsolver (const DenseQPsolver &rhs)
 
virtual uint getNumberOfIterations () const
 
QPStatus getStatus () const
 
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)
 
 ~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 setupQPobject (uint nV, uint nC)
 
returnValue updateQPstatus (int ret)
 
- Protected Member Functions inherited from DenseQPsolver
virtual returnValue makeBoundsConsistent (DenseCP *cp) const
 
virtual returnValue setupLogging ()
 
- Protected Member Functions inherited from DenseCPsolver
virtual returnValue setupOptions ()
 

Protected Attributes

qpOASES::SQProblem * qp
 
- Protected Attributes inherited from DenseQPsolver
int numberOfSteps
 
QPStatus qpStatus
 
- Protected Attributes inherited from AlgorithmicBase
int outputLoggingIdx
 
BooleanType useModuleStandalone
 
UserInteractionuserInteraction
 

Detailed Description

(not yet documented)

The class QPsolver_qpOASES interfaces the qpOASES software package for solving convex quadratic programming (QP) problems.

 \author Boris Houska, Hans Joachim Ferreau

Definition at line 57 of file qp_solver_qpoases.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_ACADO QPsolver_qpOASES::QPsolver_qpOASES ( )

Default constructor.

Definition at line 44 of file qp_solver_qpoases.cpp.

QPsolver_qpOASES::QPsolver_qpOASES ( UserInteraction _userInteraction)

Definition at line 50 of file qp_solver_qpoases.cpp.

QPsolver_qpOASES::QPsolver_qpOASES ( const QPsolver_qpOASES rhs)

Copy constructor (deep copy).

Definition at line 56 of file qp_solver_qpoases.cpp.

QPsolver_qpOASES::~QPsolver_qpOASES ( )
virtual

Destructor.

Definition at line 65 of file qp_solver_qpoases.cpp.

Member Function Documentation

DenseCPsolver * QPsolver_qpOASES::clone ( ) const
virtual

Implements DenseQPsolver.

Definition at line 93 of file qp_solver_qpoases.cpp.

DenseQPsolver * QPsolver_qpOASES::cloneDenseQPsolver ( ) const
virtual

Implements DenseQPsolver.

Definition at line 99 of file qp_solver_qpoases.cpp.

returnValue QPsolver_qpOASES::getDualSolution ( DVector yOpt) const
virtual

Returns dual solution vector if QP has been solved.

Returns
SUCCESSFUL_RETURN
RET_QP_NOT_SOLVED
Parameters
yOptOUTPUT: dual solution vector.

Implements DenseQPsolver.

Definition at line 230 of file qp_solver_qpoases.cpp.

uint QPsolver_qpOASES::getNumberOfConstraints ( ) const
virtual

Implements DenseQPsolver.

Definition at line 278 of file qp_solver_qpoases.cpp.

uint QPsolver_qpOASES::getNumberOfVariables ( ) const
virtual

Implements DenseQPsolver.

Definition at line 270 of file qp_solver_qpoases.cpp.

double QPsolver_qpOASES::getObjVal ( ) const
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

Implements DenseQPsolver.

Definition at line 252 of file qp_solver_qpoases.cpp.

returnValue QPsolver_qpOASES::getPrimalSolution ( DVector xOpt) const
virtual

Returns primal solution vector if QP has been solved.

Returns
SUCCESSFUL_RETURN
RET_QP_NOT_SOLVED
Parameters
xOptOUTPUT: primal solution vector.

Implements DenseQPsolver.

Definition at line 208 of file qp_solver_qpoases.cpp.

returnValue QPsolver_qpOASES::getVarianceCovariance ( DMatrix var)
virtual

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

Returns
SUCCESSFUL_RETURN RET_MEMBER_NOT_INITIALISED

Implements DenseQPsolver.

Definition at line 264 of file qp_solver_qpoases.cpp.

returnValue QPsolver_qpOASES::getVarianceCovariance ( DMatrix H,
DMatrix var 
)
virtual

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

Returns
SUCCESSFUL_RETURN RET_MEMBER_NOT_INITIALISED

Implements DenseQPsolver.

Definition at line 287 of file qp_solver_qpoases.cpp.

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

Assignment operator (deep copy).

Definition at line 72 of file qp_solver_qpoases.cpp.

returnValue QPsolver_qpOASES::setupQPobject ( uint  nV,
uint  nC 
)
protectedvirtual

Setups QP object.

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

Implements DenseQPsolver.

Definition at line 339 of file qp_solver_qpoases.cpp.

returnValue QPsolver_qpOASES::solve ( DenseCP cp_)
virtual

Solves the QP.

Reimplemented from DenseQPsolver.

Definition at line 105 of file qp_solver_qpoases.cpp.

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

Solves QP using at most <maxIter> iterations.

Returns
SUCCESSFUL_RETURN
RET_QP_SOLUTION_REACHED_LIMIT
RET_QP_SOLUTION_FAILED
RET_INITIALIZE_FIRST
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.

Implements DenseQPsolver.

Definition at line 111 of file qp_solver_qpoases.cpp.

returnValue QPsolver_qpOASES::solve ( DMatrix H,
DMatrix A,
DVector g,
DVector lb,
DVector ub,
DVector lbA,
DVector ubA,
uint  maxIter 
)
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.

Implements DenseQPsolver.

Definition at line 158 of file qp_solver_qpoases.cpp.

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

Performs exactly one QP iteration.

Returns
SUCCESSFUL_RETURN
RET_QP_SOLUTION_REACHED_LIMIT
RET_QP_SOLUTION_FAILED
RET_INITIALIZE_FIRST
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.

Implements DenseQPsolver.

Definition at line 180 of file qp_solver_qpoases.cpp.

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

Performs exactly one QP iteration.

Returns
SUCCESSFUL_RETURN
RET_QP_SOLUTION_REACHED_LIMIT
RET_QP_SOLUTION_FAILED
RET_INITIALIZE_FIRST
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.

Implements DenseQPsolver.

Definition at line 194 of file qp_solver_qpoases.cpp.

returnValue QPsolver_qpOASES::updateQPstatus ( int  ret)
protected

Definition at line 377 of file qp_solver_qpoases.cpp.

Member Data Documentation

qpOASES::SQProblem* QPsolver_qpOASES::qp
protected

Definition at line 204 of file qp_solver_qpoases.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:26