Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | Friends | List of all members
QProblemB Struct Reference

Implements the online active set strategy for box-constrained QPs. More...

#include <QProblemB.hpp>

Inheritance diagram for QProblemB:
Inheritance graph
[legend]

Public Member Functions

returnValue getBounds (Bounds *const _bounds) const
 
returnValue getBounds (Bounds *const _bounds) const
 
returnValue getBounds (Bounds &_bounds) const
 
returnValue getBounds (Bounds &_bounds) const
 
uint_t getCount () const
 
returnValue getDualSolution (real_t *const yOpt) const
 
returnValue getDualSolution (real_t *const yOpt) const
 
virtual returnValue getDualSolution (real_t *const yOpt) const
 
virtual returnValue getDualSolution (real_t *const yOpt) const
 
returnValue getG (real_t *const _g) const
 
returnValue getG (real_t *const _g) const
 
returnValue getH (real_t *const _H) const
 
returnValue getH (real_t *const _H) const
 
HessianType getHessianType () const
 
HessianType getHessianType () const
 
HessianType getHessianType () const
 
HessianType getHessianType () const
 
returnValue getLB (real_t *const _lb) const
 
returnValue getLB (int number, real_t &value) const
 
returnValue getLB (real_t *const _lb) const
 
returnValue getLB (int number, real_t &value) const
 
int getNFR ()
 
int getNFR ()
 
int_t getNFR () const
 
int getNFR () const
 
int getNFV () const
 
int getNFV () const
 
int_t getNFV () const
 
int getNFV () const
 
int getNFX ()
 
int getNFX ()
 
int_t getNFX () const
 
int getNFX () const
 
int getNV () const
 
int getNV () const
 
int_t getNV () const
 
int getNV () const
 
int getNZ ()
 
int getNZ ()
 
virtual int_t getNZ () const
 
virtual int getNZ () const
 
real_t getObjVal () const
 
real_t getObjVal (const real_t *const _x) const
 
real_t getObjVal () const
 
real_t getObjVal (const real_t *const _x) const
 
real_t getObjVal () const
 
real_t getObjVal (const real_t *const _x) const
 
real_t getObjVal () const
 
real_t getObjVal (const real_t *const _x) const
 
Options getOptions () const
 
Options getOptions () const
 
returnValue getPrimalSolution (real_t *const xOpt) const
 
returnValue getPrimalSolution (real_t *const xOpt) const
 
returnValue getPrimalSolution (real_t *const xOpt) const
 
returnValue getPrimalSolution (real_t *const xOpt) const
 
PrintLevel getPrintLevel () const
 
PrintLevel getPrintLevel () const
 
PrintLevel getPrintLevel () const
 
PrintLevel getPrintLevel () const
 
QProblemStatus getStatus () const
 
QProblemStatus getStatus () const
 
QProblemStatus getStatus () const
 
QProblemStatus getStatus () const
 
returnValue getUB (real_t *const _ub) const
 
returnValue getUB (int number, real_t &value) const
 
returnValue getUB (real_t *const _ub) const
 
returnValue getUB (int number, real_t &value) const
 
virtual returnValue getWorkingSet (real_t *workingSet)
 
virtual returnValue getWorkingSetBounds (real_t *workingSetB)
 
virtual returnValue getWorkingSetConstraints (real_t *workingSetC)
 
returnValue hotstart (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, int &nWSR, real_t *const cputime)
 
returnValue hotstart (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, int &nWSR, real_t *const cputime)
 
returnValue hotstart (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, int_t &nWSR, real_t *const cputime=0, const Bounds *const guessedBounds=0)
 
returnValue hotstart (const char *const g_file, const char *const lb_file, const char *const ub_file, int_t &nWSR, real_t *const cputime=0, const Bounds *const guessedBounds=0)
 
returnValue hotstart (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, int &nWSR, real_t *const cputime)
 
returnValue hotstart (const char *const g_file, const char *const lb_file, const char *const ub_file, int &nWSR, real_t *const cputime)
 
returnValue hotstart (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, int &nWSR, real_t *const cputime, const Bounds *const guessedBounds)
 
returnValue hotstart (const char *const g_file, const char *const lb_file, const char *const ub_file, int &nWSR, real_t *const cputime, const Bounds *const guessedBounds)
 
returnValue init (const real_t *const _H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub, int &nWSR, const real_t *const yOpt=0, real_t *const cputime=0)
 
returnValue init (const real_t *const _H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub, int &nWSR, const real_t *const yOpt=0, real_t *const cputime=0)
 
returnValue init (SymmetricMatrix *_H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub, int &nWSR, real_t *const cputime)
 
returnValue init (SymmetricMatrix *_H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub, int_t &nWSR, real_t *const cputime=0, const real_t *const xOpt=0, const real_t *const yOpt=0, const Bounds *const guessedBounds=0, const real_t *const _R=0)
 
returnValue init (const real_t *const _H, const real_t *const _R, const real_t *const _g, const real_t *const _lb, const real_t *const _ub, int &nWSR, const real_t *const yOpt=0, real_t *const cputime=0)
 
returnValue init (const real_t *const _H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub, int &nWSR, real_t *const cputime)
 
returnValue init (const char *const H_file, const char *const g_file, const char *const lb_file, const char *const ub_file, int &nWSR, real_t *const cputime)
 
returnValue init (const real_t *const _H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub, int_t &nWSR, real_t *const cputime=0, const real_t *const xOpt=0, const real_t *const yOpt=0, const Bounds *const guessedBounds=0, const real_t *const _R=0)
 
returnValue init (SymmetricMatrix *_H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub, int &nWSR, real_t *const cputime, const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds)
 
returnValue init (const char *const H_file, const char *const g_file, const char *const lb_file, const char *const ub_file, int_t &nWSR, real_t *const cputime=0, const real_t *const xOpt=0, const real_t *const yOpt=0, const Bounds *const guessedBounds=0, const char *const R_file=0)
 
returnValue init (const real_t *const _H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub, int &nWSR, real_t *const cputime, const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds)
 
returnValue init (const char *const H_file, const char *const g_file, const char *const lb_file, const char *const ub_file, int &nWSR, real_t *const cputime, const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds)
 
BooleanType isInfeasible () const
 
BooleanType isInfeasible () const
 
BooleanType isInfeasible () const
 
BooleanType isInfeasible () const
 
BooleanType isInitialised () const
 
BooleanType isInitialised () const
 
BooleanType isInitialised () const
 
BooleanType isInitialised () const
 
BooleanType isSolved () const
 
BooleanType isSolved () const
 
BooleanType isSolved () const
 
BooleanType isSolved () const
 
BooleanType isUnbounded () const
 
BooleanType isUnbounded () const
 
BooleanType isUnbounded () const
 
BooleanType isUnbounded () const
 
QProblemBoperator= (const QProblemB &rhs)
 
QProblemBoperator= (const QProblemB &rhs)
 
QProblemBoperator= (const QProblemB &rhs)
 
virtual QProblemBoperator= (const QProblemB &rhs)
 
returnValue printOptions () const
 
returnValue printOptions () const
 
virtual returnValue printProperties ()
 
virtual returnValue printProperties ()
 
 QProblemB ()
 
 QProblemB ()
 
 QProblemB (int _nV)
 
 QProblemB (int _nV)
 
 QProblemB (const QProblemB &rhs)
 
 QProblemB (const QProblemB &rhs)
 
 QProblemB ()
 
 QProblemB ()
 
 QProblemB (int_t _nV, HessianType _hessianType=HST_UNKNOWN)
 
 QProblemB (int _nV, HessianType _hessianType=HST_UNKNOWN)
 
 QProblemB (const QProblemB &rhs)
 
 QProblemB (const QProblemB &rhs)
 
returnValue reset ()
 
returnValue reset ()
 
virtual returnValue reset ()
 
virtual returnValue reset ()
 
returnValue resetCounter ()
 
returnValue setHessianType (HessianType _hessianType)
 
returnValue setHessianType (HessianType _hessianType)
 
returnValue setHessianType (HessianType _hessianType)
 
returnValue setHessianType (HessianType _hessianType)
 
returnValue setOptions (const Options &_options)
 
returnValue setOptions (const Options &_options)
 
returnValue setPrintLevel (PrintLevel _printlevel)
 
returnValue setPrintLevel (PrintLevel _printlevel)
 
returnValue setPrintLevel (PrintLevel _printlevel)
 
returnValue setPrintLevel (PrintLevel _printlevel)
 
BooleanType usingRegularisation () const
 
BooleanType usingRegularisation () const
 
 ~QProblemB ()
 
 ~QProblemB ()
 
virtual ~QProblemB ()
 
virtual ~QProblemB ()
 

Public Attributes

unsigned int count
 
real_t delta_xFR_TMP [NVMAX]
 
DenseMatrixH
 
DenseMatrix HH
 
int rampOffset
 

Protected Member Functions

returnValue addBound (int number, SubjectToStatus B_status, BooleanType updateCholesky)
 
returnValue addBound (int number, SubjectToStatus B_status, BooleanType updateCholesky)
 
void applyGivens (real_t c, real_t s, real_t xold, real_t yold, real_t &xnew, real_t &ynew) const
 
void applyGivens (real_t c, real_t s, real_t xold, real_t yold, real_t &xnew, real_t &ynew) const
 
void applyGivens (real_t c, real_t s, real_t nu, real_t xold, real_t yold, real_t &xnew, real_t &ynew) const
 
void applyGivens (real_t c, real_t s, real_t nu, real_t xold, real_t yold, real_t &xnew, real_t &ynew) const
 
BooleanType areBoundsConsistent (const real_t *const delta_lb, const real_t *const delta_ub) const
 
BooleanType areBoundsConsistent (const real_t *const delta_lb, const real_t *const delta_ub) const
 
returnValue areBoundsConsistent (const real_t *const lb, const real_t *const ub) const
 
returnValue backsolveR (const real_t *const b, BooleanType transposed, real_t *const a)
 
returnValue backsolveR (const real_t *const b, BooleanType transposed, BooleanType removingBound, real_t *const a)
 
returnValue backsolveR (const real_t *const b, BooleanType transposed, real_t *const a)
 
returnValue backsolveR (const real_t *const b, BooleanType transposed, BooleanType removingBound, real_t *const a)
 
virtual returnValue backsolveR (const real_t *const b, BooleanType transposed, real_t *const a) const
 
virtual returnValue backsolveR (const real_t *const b, BooleanType transposed, BooleanType removingBound, real_t *const a) const
 
returnValue backsolveR (const real_t *const b, BooleanType transposed, real_t *const a) const
 
returnValue backsolveR (const real_t *const b, BooleanType transposed, BooleanType removingBound, real_t *const a) const
 
returnValue checkForIdentityHessian ()
 
returnValue checkForIdentityHessian ()
 
returnValue clear ()
 
returnValue clear ()
 
virtual returnValue computeCholesky ()
 
void computeGivens (real_t xold, real_t yold, real_t &xnew, real_t &ynew, real_t &c, real_t &s) const
 
void computeGivens (real_t xold, real_t yold, real_t &xnew, real_t &ynew, real_t &c, real_t &s) const
 
void computeGivens (real_t xold, real_t yold, real_t &xnew, real_t &ynew, real_t &c, real_t &s) const
 
void computeGivens (real_t xold, real_t yold, real_t &xnew, real_t &ynew, real_t &c, real_t &s) const
 
returnValue copy (const QProblemB &rhs)
 
returnValue copy (const QProblemB &rhs)
 
SymSparseMatcreateDiagSparseMat (int_t n, real_t diagVal=1.0)
 
returnValue determineDataShift (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, real_t *const delta_g, real_t *const delta_lb, real_t *const delta_ub, BooleanType &Delta_bB_isZero)
 
returnValue determineDataShift (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, real_t *const delta_g, real_t *const delta_lb, real_t *const delta_ub, BooleanType &Delta_bB_isZero)
 
returnValue determineHessianType ()
 
returnValue determineHessianType ()
 
real_t getRelativeHomotopyLength (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new)
 
returnValue hotstart_determineDataShift (const int *const FX_idx, const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, real_t *const delta_g, real_t *const delta_lb, real_t *const delta_ub, BooleanType &Delta_bB_isZero)
 
returnValue hotstart_determineDataShift (const int *const FX_idx, const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, real_t *const delta_g, real_t *const delta_lb, real_t *const delta_ub, BooleanType &Delta_bB_isZero)
 
BooleanType isBlocking (real_t num, real_t den, real_t epsNum, real_t epsDen, real_t &t) const
 
BooleanType isBlocking (real_t num, real_t den, real_t epsNum, real_t epsDen, real_t &t) const
 
BooleanType isCPUtimeLimitExceeded (const real_t *const cputime, real_t starttime, int_t nWSR) const
 
BooleanType isCPUtimeLimitExceeded (const real_t *const cputime, real_t starttime, int nWSR) const
 
returnValue loadQPvectorsFromFile (const char *const g_file, const char *const lb_file, const char *const ub_file, real_t *const g_new, real_t *const lb_new, real_t *const ub_new) const
 
returnValue loadQPvectorsFromFile (const char *const g_file, const char *const lb_file, const char *const ub_file, real_t *const g_new, real_t *const lb_new, real_t *const ub_new) const
 
returnValue obtainAuxiliaryWorkingSet (const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds, Bounds *auxiliaryBounds) const
 
returnValue obtainAuxiliaryWorkingSet (const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds, Bounds *auxiliaryBounds) const
 
returnValue obtainAuxiliaryWorkingSet (const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds, Bounds *auxiliaryBounds) const
 
returnValue obtainAuxiliaryWorkingSet (const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds, Bounds *auxiliaryBounds) const
 
virtual returnValue performRamping ()
 
virtual returnValue performRamping ()
 
returnValue performRatioTest (int_t nIdx, const int_t *const idxList, const SubjectTo *const subjectTo, const real_t *const num, const real_t *const den, real_t epsNum, real_t epsDen, real_t &t, int_t &BC_idx) const
 
returnValue performRatioTest (int nIdx, const int *const idxList, const SubjectTo *const subjectTo, const real_t *const num, const real_t *const den, real_t epsNum, real_t epsDen, real_t &t, int &BC_idx) const
 
returnValue regulariseHessian ()
 
returnValue regulariseHessian ()
 
real_t relativeHomotopyLength (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new)
 
returnValue removeBound (int number, BooleanType updateCholesky)
 
returnValue removeBound (int number, BooleanType updateCholesky)
 
returnValue setG (const real_t *const g_new)
 
returnValue setG (const real_t *const g_new)
 
returnValue setG (const real_t *const g_new)
 
returnValue setG (const real_t *const g_new)
 
returnValue setH (const real_t *const H_new)
 
returnValue setH (const real_t *const H_new)
 
returnValue setH (SymmetricMatrix *H_new)
 
returnValue setH (const real_t *const H_new)
 
returnValue setH (SymmetricMatrix *H_new)
 
returnValue setH (const real_t *const H_new)
 
returnValue setInfeasibilityFlag (returnValue returnvalue, BooleanType doThrowError=BT_FALSE)
 
returnValue setInfeasibilityFlag (returnValue returnvalue)
 
returnValue setLB (const real_t *const lb_new)
 
returnValue setLB (int number, real_t value)
 
returnValue setLB (const real_t *const lb_new)
 
returnValue setLB (int number, real_t value)
 
returnValue setLB (const real_t *const lb_new)
 
returnValue setLB (int_t number, real_t value)
 
returnValue setLB (const real_t *const lb_new)
 
returnValue setLB (int number, real_t value)
 
returnValue setUB (const real_t *const ub_new)
 
returnValue setUB (int number, real_t value)
 
returnValue setUB (const real_t *const ub_new)
 
returnValue setUB (int number, real_t value)
 
returnValue setUB (const real_t *const ub_new)
 
returnValue setUB (int_t number, real_t value)
 
returnValue setUB (const real_t *const ub_new)
 
returnValue setUB (int number, real_t value)
 
virtual returnValue setupAuxiliaryQP (const Bounds *const guessedBounds)
 
returnValue setupAuxiliaryQPbounds (BooleanType useRelaxation)
 
returnValue setupAuxiliaryQPbounds (BooleanType useRelaxation)
 
returnValue setupAuxiliaryQPgradient ()
 
returnValue setupAuxiliaryQPgradient ()
 
returnValue setupAuxiliaryQPsolution (const real_t *const xOpt, const real_t *const yOpt)
 
returnValue setupAuxiliaryQPsolution (const real_t *const xOpt, const real_t *const yOpt)
 
returnValue setupAuxiliaryWorkingSet (const Bounds *const auxiliaryBounds, BooleanType setupAfresh)
 
returnValue setupAuxiliaryWorkingSet (const Bounds *const auxiliaryBounds, BooleanType setupAfresh)
 
returnValue setupCholeskyDecomposition ()
 
returnValue setupCholeskyDecomposition ()
 
returnValue setupCholeskyDecomposition ()
 
virtual returnValue setupInitialCholesky ()
 
returnValue setupQPdata (const real_t *const _H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub)
 
returnValue setupQPdata (const real_t *const _H, const real_t *const _R, const real_t *const _g, const real_t *const _lb, const real_t *const _ub)
 
returnValue setupQPdata (SymmetricMatrix *_H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub)
 
returnValue setupQPdata (const real_t *const _H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub)
 
returnValue setupQPdata (SymmetricMatrix *_H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub)
 
returnValue setupQPdata (const real_t *const _H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub)
 
returnValue setupQPdataFromFile (const char *const H_file, const char *const g_file, const char *const lb_file, const char *const ub_file)
 
returnValue setupQPdataFromFile (const char *const H_file, const char *const g_file, const char *const lb_file, const char *const ub_file)
 
returnValue setupSubjectToType ()
 
returnValue setupSubjectToType ()
 
virtual returnValue setupSubjectToType ()
 
virtual returnValue setupSubjectToType (const real_t *const lb_new, const real_t *const ub_new)
 
virtual returnValue setupSubjectToType ()
 
virtual returnValue setupSubjectToType (const real_t *const lb_new, const real_t *const ub_new)
 
returnValue solveInitialQP (const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds, int &nWSR, real_t *const cputime)
 
returnValue solveInitialQP (const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds, int &nWSR, real_t *const cputime)
 
returnValue updateFarBounds (real_t curFarBound, int_t nRamp, const real_t *const lb_new, real_t *const lb_new_far, const real_t *const ub_new, real_t *const ub_new_far) const
 

Protected Attributes

Bounds bounds
 
int count
 
uint_t count
 
real_tdelta_xFR_TMP
 
Flipper flipper
 
BooleanType freeHessian
 
real_t g [NVMAX]
 
real_tg
 
real_t H [NVMAX *NVMAX]
 
SymmetricMatrixH
 
BooleanType hasCholesky
 
BooleanType hasHessian
 
BooleanType haveCholesky
 
HessianType hessianType
 
BooleanType infeasible
 
BooleanType isRegularised
 
real_t lb [NVMAX]
 
real_tlb
 
Options options
 
PrintLevel printlevel
 
real_t R [NVMAX *NVMAX]
 
real_tR
 
real_t ramp0
 
real_t ramp1
 
int_t rampOffset
 
real_t regVal
 
QProblemStatus status
 
TabularOutput tabularOutput
 
real_t tau
 
real_t ub [NVMAX]
 
real_tub
 
BooleanType unbounded
 
real_t x [NVMAX]
 
real_tx
 
real_t y [NVMAX+NCMAX]
 
real_ty
 

Private Member Functions

returnValue addBound (int_t number, SubjectToStatus B_status, BooleanType updateCholesky)
 
returnValue addBound (int number, SubjectToStatus B_status, BooleanType updateCholesky)
 
returnValue changeActiveSet (int_t BC_idx, SubjectToStatus BC_status)
 
returnValue changeActiveSet (int BC_idx, SubjectToStatus BC_status)
 
returnValue checkKKTconditions ()
 
returnValue checkKKTconditions ()
 
returnValue determineStepDirection (const real_t *const delta_g, const real_t *const delta_lb, const real_t *const delta_ub, BooleanType Delta_bB_isZero, real_t *const delta_xFX, real_t *const delta_xFR, real_t *const delta_yFX)
 
returnValue determineStepDirection (const real_t *const delta_g, const real_t *const delta_lb, const real_t *const delta_ub, BooleanType Delta_bB_isZero, real_t *const delta_xFX, real_t *const delta_xFR, real_t *const delta_yFX)
 
returnValue hotstart_determineStepDirection (const int *const FR_idx, const int *const FX_idx, const real_t *const delta_g, const real_t *const delta_lb, const real_t *const delta_ub, BooleanType Delta_bB_isZero, real_t *const delta_xFX, real_t *const delta_xFR, real_t *const delta_yFX)
 
returnValue hotstart_determineStepDirection (const int *const FR_idx, const int *const FX_idx, const real_t *const delta_g, const real_t *const delta_lb, const real_t *const delta_ub, BooleanType Delta_bB_isZero, real_t *const delta_xFX, real_t *const delta_xFR, real_t *const delta_yFX)
 
returnValue hotstart_determineStepLength (const int *const FR_idx, const int *const FX_idx, const real_t *const delta_lb, const real_t *const delta_ub, const real_t *const delta_xFR, const real_t *const delta_yFX, int &BC_idx, SubjectToStatus &BC_status)
 
returnValue hotstart_determineStepLength (const int *const FR_idx, const int *const FX_idx, const real_t *const delta_lb, const real_t *const delta_ub, const real_t *const delta_xFR, const real_t *const delta_yFX, int &BC_idx, SubjectToStatus &BC_status)
 
returnValue hotstart_performStep (const int *const FR_idx, const int *const FX_idx, const real_t *const delta_g, const real_t *const delta_lb, const real_t *const delta_ub, const real_t *const delta_xFX, const real_t *const delta_xFR, const real_t *const delta_yFX, int BC_idx, SubjectToStatus BC_status)
 
returnValue hotstart_performStep (const int *const FR_idx, const int *const FX_idx, const real_t *const delta_g, const real_t *const delta_lb, const real_t *const delta_ub, const real_t *const delta_xFX, const real_t *const delta_xFR, const real_t *const delta_yFX, int BC_idx, SubjectToStatus BC_status)
 
virtual returnValue performDriftCorrection ()
 
returnValue performDriftCorrection ()
 
returnValue performStep (const real_t *const delta_g, const real_t *const delta_lb, const real_t *const delta_ub, const real_t *const delta_xFX, const real_t *const delta_xFR, const real_t *const delta_yFX, int_t &BC_idx, SubjectToStatus &BC_status)
 
returnValue performStep (const real_t *const delta_g, const real_t *const delta_lb, const real_t *const delta_ub, const real_t *const delta_xFX, const real_t *const delta_xFR, const real_t *const delta_yFX, int &BC_idx, SubjectToStatus &BC_status)
 
returnValue printIteration (int_t iter, int_t BC_idx, SubjectToStatus BC_status, real_t homotopyLength, BooleanType isFirstCall=BT_TRUE)
 
returnValue printIteration (int iteration, int BC_idx, SubjectToStatus BC_status)
 
returnValue removeBound (int_t number, BooleanType updateCholesky)
 
returnValue removeBound (int number, BooleanType updateCholesky)
 
returnValue setupAuxiliaryQP (const Bounds *const guessedBounds)
 
returnValue setupAuxiliaryQPbounds (BooleanType useRelaxation)
 
returnValue setupAuxiliaryQPbounds (BooleanType useRelaxation)
 
returnValue setupAuxiliaryQPgradient ()
 
returnValue setupAuxiliaryQPgradient ()
 
returnValue setupAuxiliaryQPsolution (const real_t *const xOpt, const real_t *const yOpt)
 
returnValue setupAuxiliaryQPsolution (const real_t *const xOpt, const real_t *const yOpt)
 
returnValue setupAuxiliaryWorkingSet (const Bounds *const auxiliaryBounds, BooleanType setupAfresh)
 
returnValue setupAuxiliaryWorkingSet (const Bounds *const auxiliaryBounds, BooleanType setupAfresh)
 
BooleanType shallRefactorise (const Bounds *const guessedBounds) const
 
BooleanType shallRefactorise (const Bounds *const guessedBounds) const
 
returnValue solveInitialQP (const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds, const real_t *const _R, int_t &nWSR, real_t *const cputime)
 
returnValue solveInitialQP (const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds, int &nWSR, real_t *const cputime)
 
returnValue solveQP (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, int_t &nWSR, real_t *const cputime, int_t nWSRperformed=0, BooleanType isFirstCall=BT_TRUE)
 
returnValue solveQP (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, int &nWSR, real_t *const cputime, int nWSRperformed=0)
 
returnValue solveRegularisedQP (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, int_t &nWSR, real_t *const cputime, int_t nWSRperformed=0, BooleanType isFirstCall=BT_TRUE)
 
returnValue solveRegularisedQP (const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new, int &nWSR, real_t *const cputime, int nWSRperformed=0)
 

Friends

class SolutionAnalysis
 

Detailed Description

Implements the online active set strategy for box-constrained QPs.

Class for setting up and solving quadratic programs with (simple) bounds only. The main feature is the possibily to use the newly developed online active set strategy for parametric quadratic programming.

Author
Hans Joachim Ferreau
Version
1.3embedded
Date
2007-2008

Class for setting up and solving quadratic programs with bounds (= box constraints) only. The main feature is the possibily to use the newly developed online active set strategy for parametric quadratic programming.

Author
Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
Version
3.0beta
Date
2007-2011

Class for setting up and solving quadratic programs with bounds (= box constraints) only. The main feature is the possibily to use the newly developed online active set strategy for parametric quadratic programming.

Author
Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
Version
3.2
Date
2007-2015

Class for setting up and solving quadratic programs with bounds (= box constraints) only. The main feature is the possibility to use the newly developed online active set strategy for parametric quadratic programming.

Author
Hans Joachim Ferreau, Andreas Potschka, Christian Kirches
Version
3.1embedded
Date
2007-2015

Definition at line 55 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/INCLUDE/QProblemB.hpp.

Constructor & Destructor Documentation

BEGIN_NAMESPACE_QPOASES QProblemB::QProblemB ( )
QProblemB::QProblemB ( int  _nV)

Constructor which takes the QP dimension only.

Parameters
_nVNumber of variables.

Definition at line 90 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

QProblemB::QProblemB ( const QProblemB rhs)

Copy constructor (deep copy).

Parameters
rhsRhs object.

Definition at line 126 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

QProblemB::~QProblemB ( )
QProblemB::QProblemB ( )

Default constructor.

QProblemB::QProblemB ( int  _nV)

Constructor which takes the QP dimension only.

Parameters
_nVNumber of variables.
QProblemB::QProblemB ( const QProblemB rhs)

Copy constructor (deep copy).

Parameters
rhsRhs object.
QProblemB::~QProblemB ( )

Destructor.

QProblemB::QProblemB ( )

Default constructor.

QProblemB::QProblemB ( int  _nV,
HessianType  _hessianType = HST_UNKNOWN 
)

Constructor which takes the QP dimension and Hessian type information. If the Hessian is the zero (i.e. HST_ZERO) or the identity matrix (i.e. HST_IDENTITY), respectively, no memory is allocated for it and a NULL pointer can be passed for it to the init() functions.

Parameters
_nVNumber of variables.
_hessianTypeType of Hessian matrix.

Definition at line 95 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

QProblemB::QProblemB ( const QProblemB rhs)

Copy constructor (deep copy).

Parameters
rhsRhs object.
virtual QProblemB::~QProblemB ( )
virtual

Destructor.

QProblemB::QProblemB ( )

Default constructor.

QProblemB::QProblemB ( int_t  _nV,
HessianType  _hessianType = HST_UNKNOWN 
)

Constructor which takes the QP dimension and Hessian type information. If the Hessian is the zero (i.e. HST_ZERO) or the identity matrix (i.e. HST_IDENTITY), respectively, no memory is allocated for it and a NULL pointer can be passed for it to the init() functions.

Parameters
_nVNumber of variables.
_hessianTypeType of Hessian matrix.
QProblemB::QProblemB ( const QProblemB rhs)

Copy constructor (deep copy).

Parameters
rhsRhs object.
virtual QProblemB::~QProblemB ( )
virtual

Destructor.

Member Function Documentation

returnValue QProblemB::addBound ( int  number,
SubjectToStatus  B_status,
BooleanType  updateCholesky 
)
protected

Adds a bound to active set (specialised version for the case where no constraints exist).

Returns
SUCCESSFUL_RETURN
RET_ADDBOUND_FAILED
Parameters
numberNumber of bound to be added to active set.
B_statusStatus of new active bound.
updateCholeskyFlag indicating if Cholesky decomposition shall be updated.

Definition at line 1226 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::addBound ( int  number,
SubjectToStatus  B_status,
BooleanType  updateCholesky 
)
protected

Adds a bound to active set (specialised version for the case where no constraints exist).

Returns
SUCCESSFUL_RETURN
RET_ADDBOUND_FAILED
Parameters
numberNumber of bound to be added to active set.
B_statusStatus of new active bound.
updateCholeskyFlag indicating if Cholesky decomposition shall be updated.
returnValue QProblemB::addBound ( int_t  number,
SubjectToStatus  B_status,
BooleanType  updateCholesky 
)
private

Adds a bound to active set (specialised version for the case where no constraints exist).

Returns
SUCCESSFUL_RETURN
RET_ADDBOUND_FAILED
Parameters
numberNumber of bound to be added to active set.
B_statusStatus of new active bound.
updateCholeskyFlag indicating if Cholesky decomposition shall be updated.
returnValue QProblemB::addBound ( int  number,
SubjectToStatus  B_status,
BooleanType  updateCholesky 
)
private

Adds a bound to active set (specialised version for the case where no constraints exist).

Returns
SUCCESSFUL_RETURN
RET_ADDBOUND_FAILED
Parameters
numberNumber of bound to be added to active set.
B_statusStatus of new active bound.
updateCholeskyFlag indicating if Cholesky decomposition shall be updated.
void QProblemB::applyGivens ( real_t  c,
real_t  s,
real_t  xold,
real_t  yold,
real_t xnew,
real_t ynew 
) const
inlineprotected

Applies Givens matrix determined by c and s (cf. computeGivens).

Returns
SUCCESSFUL_RETURN
Parameters
cCosine entry of Givens matrix.
sSine entry of Givens matrix.
xoldMatrix entry to be transformed corresponding to the normalised entry of the original matrix.
yoldMatrix entry to be transformed corresponding to the annihilated entry of the original matrix.
xnewOutput: Transformed matrix entry corresponding to the normalised entry of the original matrix.
ynewOutput: Transformed matrix entry corresponding to the annihilated entry of the original matrix.
void QProblemB::applyGivens ( real_t  c,
real_t  s,
real_t  xold,
real_t  yold,
real_t xnew,
real_t ynew 
) const
inlineprotected

Applies Givens matrix determined by c and s (cf. computeGivens).

Returns
SUCCESSFUL_RETURN
Parameters
cCosine entry of Givens matrix.
sSine entry of Givens matrix.
xoldMatrix entry to be transformed corresponding to the normalised entry of the original matrix.
yoldMatrix entry to be transformed corresponding to the annihilated entry of the original matrix.
xnewOutput: Transformed matrix entry corresponding to the normalised entry of the original matrix.
ynewOutput: Transformed matrix entry corresponding to the annihilated entry of the original matrix.
void QProblemB::applyGivens ( real_t  c,
real_t  s,
real_t  nu,
real_t  xold,
real_t  yold,
real_t xnew,
real_t ynew 
) const
inlineprotected

Applies Givens matrix determined by c and s (cf. computeGivens).

Returns
SUCCESSFUL_RETURN
Parameters
cCosine entry of Givens matrix.
sSine entry of Givens matrix.
nuFurther factor: s/(1+c).
xoldMatrix entry to be transformed corresponding to the normalised entry of the original matrix.
yoldMatrix entry to be transformed corresponding to the annihilated entry of the original matrix.
xnewOutput: Transformed matrix entry corresponding to the normalised entry of the original matrix.
ynewOutput: Transformed matrix entry corresponding to the annihilated entry of the original matrix.
void QProblemB::applyGivens ( real_t  c,
real_t  s,
real_t  nu,
real_t  xold,
real_t  yold,
real_t xnew,
real_t ynew 
) const
inlineprotected

Applies Givens matrix determined by c and s (cf. computeGivens).

Returns
SUCCESSFUL_RETURN
Parameters
cCosine entry of Givens matrix.
sSine entry of Givens matrix.
nuFurther factor: s/(1+c).
xoldMatrix entry to be transformed corresponding to the normalised entry of the original matrix.
yoldMatrix entry to be transformed corresponding to the annihilated entry of the original matrix.
xnewOutput: Transformed matrix entry corresponding to the normalised entry of the original matrix.
ynewOutput: Transformed matrix entry corresponding to the annihilated entry of the original matrix.
returnValue QProblemB::areBoundsConsistent ( const real_t *const  delta_lb,
const real_t *const  delta_ub 
) const
protected

Checks if lower/upper bounds remain consistent (i.e. if lb <= ub) during the current step.

Returns
BT_TRUE iff bounds remain consistent
Parameters
delta_lbStep direction of lower bounds.
delta_ubStep direction of upper bounds.

Definition at line 1487 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

BooleanType QProblemB::areBoundsConsistent ( const real_t *const  delta_lb,
const real_t *const  delta_ub 
) const
protected

Checks if lower/upper bounds remain consistent (i.e. if lb <= ub) during the current step.

Returns
BT_TRUE iff bounds remain consistent
Parameters
delta_lbStep direction of lower bounds.
delta_ubStep direction of upper bounds.
returnValue QProblemB::areBoundsConsistent ( const real_t *const  lb,
const real_t *const  ub 
) const
protected

Decides if lower bounds are smaller than upper bounds

Returns
SUCCESSFUL_RETURN
RET_QP_INFEASIBLE
Parameters
lbVector of lower bounds
ubVector of upper bounds
returnValue QProblemB::backsolveR ( const real_t *const  b,
BooleanType  transposed,
real_t *const  a 
)
protected

Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.

Returns
SUCCESSFUL_RETURN
RET_DIV_BY_ZERO
Parameters
bRight hand side vector.
transposedIndicates if the transposed system shall be solved.
aOutput: Solution vector

Definition at line 1356 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::backsolveR ( const real_t *const  b,
BooleanType  transposed,
BooleanType  removingBound,
real_t *const  a 
)
protected

Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.
Special variant for the case that this function is called from within "removeBound()".

Returns
SUCCESSFUL_RETURN
RET_DIV_BY_ZERO
Parameters
bRight hand side vector.
transposedIndicates if the transposed system shall be solved.
removingBoundIndicates if function is called from "removeBound()".
aOutput: Solution vector

Definition at line 1368 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::backsolveR ( const real_t *const  b,
BooleanType  transposed,
real_t *const  a 
)
protected

Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.

Returns
SUCCESSFUL_RETURN
RET_DIV_BY_ZERO
Parameters
bRight hand side vector.
transposedIndicates if the transposed system shall be solved.
aOutput: Solution vector
returnValue QProblemB::backsolveR ( const real_t *const  b,
BooleanType  transposed,
BooleanType  removingBound,
real_t *const  a 
)
protected

Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.
Special variant for the case that this function is called from within "removeBound()".

Returns
SUCCESSFUL_RETURN
RET_DIV_BY_ZERO
Parameters
bRight hand side vector.
transposedIndicates if the transposed system shall be solved.
removingBoundIndicates if function is called from "removeBound()".
aOutput: Solution vector
virtual returnValue QProblemB::backsolveR ( const real_t *const  b,
BooleanType  transposed,
real_t *const  a 
) const
protectedvirtual

Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.

Returns
SUCCESSFUL_RETURN
RET_DIV_BY_ZERO
Parameters
bRight hand side vector.
transposedIndicates if the transposed system shall be solved.
aOutput: Solution vector

Reimplemented in SQProblemSchur.

virtual returnValue QProblemB::backsolveR ( const real_t *const  b,
BooleanType  transposed,
BooleanType  removingBound,
real_t *const  a 
) const
protectedvirtual

Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.
Special variant for the case that this function is called from within "removeBound()".

Returns
SUCCESSFUL_RETURN
RET_DIV_BY_ZERO
Parameters
bRight hand side vector.
transposedIndicates if the transposed system shall be solved.
removingBoundIndicates if function is called from "removeBound()".
aOutput: Solution vector

Reimplemented in SQProblemSchur.

returnValue QProblemB::backsolveR ( const real_t *const  b,
BooleanType  transposed,
real_t *const  a 
) const
protected

Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.

Returns
SUCCESSFUL_RETURN
RET_DIV_BY_ZERO
Parameters
bRight hand side vector.
transposedIndicates if the transposed system shall be solved.
aOutput: Solution vector

Definition at line 1653 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::backsolveR ( const real_t *const  b,
BooleanType  transposed,
BooleanType  removingBound,
real_t *const  a 
) const
protected

Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix.
Special variant for the case that this function is called from within "removeBound()".

Returns
SUCCESSFUL_RETURN
RET_DIV_BY_ZERO
Parameters
bRight hand side vector.
transposedIndicates if the transposed system shall be solved.
removingBoundIndicates if function is called from "removeBound()".
aOutput: Solution vector

Definition at line 1665 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::changeActiveSet ( int_t  BC_idx,
SubjectToStatus  BC_status 
)
private

Updates active set.

Returns
SUCCESSFUL_RETURN
RET_REMOVE_FROM_ACTIVESET_FAILED
RET_ADD_TO_ACTIVESET_FAILED
Parameters
BC_idxIndex of blocking constraint.
BC_statusStatus of blocking constraint.
returnValue QProblemB::changeActiveSet ( int  BC_idx,
SubjectToStatus  BC_status 
)
private

Updates active set.

Returns
SUCCESSFUL_RETURN
RET_REMOVE_FROM_ACTIVESET_FAILED
RET_ADD_TO_ACTIVESET_FAILED
Parameters
BC_idxIndex of blocking constraint.
BC_statusStatus of blocking constraint.

Definition at line 3270 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::checkForIdentityHessian ( )
protected

Checks if Hessian happens to be the identity matrix, and sets corresponding status flag (otherwise the flag remains unaltered!).

Returns
SUCCESSFUL_RETURN

Definition at line 631 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::checkForIdentityHessian ( )
protected

Checks if Hessian happens to be the identity matrix, and sets corresponding status flag (otherwise the flag remains unaltered!).

Returns
SUCCESSFUL_RETURN
returnValue QProblemB::checkKKTconditions ( )
private

Determines the maximum violation of the KKT optimality conditions of the current iterate within the QProblemB object.

Returns
SUCCESSFUL_RETURN
RET_INACCURATE_SOLUTION
RET_NO_SOLUTION

Definition at line 2008 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::checkKKTconditions ( )
private

Determines the maximum violation of the KKT optimality conditions of the current iterate within the QProblemB object.

Returns
SUCCESSFUL_RETURN
RET_INACCURATE_SOLUTION
RET_NO_SOLUTION
returnValue QProblemB::clear ( )
protected

Frees all allocated memory.

Returns
SUCCESSFUL_RETURN
returnValue QProblemB::clear ( )
protected

Frees all allocated memory.

Returns
SUCCESSFUL_RETURN

Definition at line 1152 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::computeCholesky ( )
protectedvirtual

Computes the Cholesky decomposition of the (simply projected) Hessian (i.e. R^T*R = Z^T*H*Z). It only works in the case where Z is a simple projection matrix! Note: If Hessian turns out not to be positive definite, the Hessian type is set to HST_SEMIDEF accordingly.

Returns
SUCCESSFUL_RETURN
RET_HESSIAN_NOT_SPD
RET_INDEXLIST_CORRUPTED

Definition at line 1360 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

void QProblemB::computeGivens ( real_t  xold,
real_t  yold,
real_t xnew,
real_t ynew,
real_t c,
real_t s 
) const
inlineprotected

Computes parameters for the Givens matrix G for which [x,y]*G = [z,0]

Returns
SUCCESSFUL_RETURN
Parameters
xoldMatrix entry to be normalised.
yoldMatrix entry to be annihilated.
xnewOutput: Normalised matrix entry.
ynewOutput: Annihilated matrix entry.
cOutput: Cosine entry of Givens matrix.
sOutput: Sine entry of Givens matrix.
void QProblemB::computeGivens ( real_t  xold,
real_t  yold,
real_t xnew,
real_t ynew,
real_t c,
real_t s 
) const
inlineprotected

Computes parameters for the Givens matrix G for which [x,y]*G = [z,0]

Returns
SUCCESSFUL_RETURN
Parameters
xoldMatrix entry to be normalised.
yoldMatrix entry to be annihilated.
xnewOutput: Normalised matrix entry.
ynewOutput: Annihilated matrix entry.
cOutput: Cosine entry of Givens matrix.
sOutput: Sine entry of Givens matrix.
void QProblemB::computeGivens ( real_t  xold,
real_t  yold,
real_t xnew,
real_t ynew,
real_t c,
real_t s 
) const
inlineprotected

Computes parameters for the Givens matrix G for which [x,y]*G = [z,0]

Returns
SUCCESSFUL_RETURN
Parameters
xoldMatrix entry to be normalised.
yoldMatrix entry to be annihilated.
xnewOutput: Normalised matrix entry.
ynewOutput: Annihilated matrix entry.
cOutput: Cosine entry of Givens matrix.
sOutput: Sine entry of Givens matrix.
void QProblemB::computeGivens ( real_t  xold,
real_t  yold,
real_t xnew,
real_t ynew,
real_t c,
real_t s 
) const
inlineprotected

Computes parameters for the Givens matrix G for which [x,y]*G = [z,0]

Returns
SUCCESSFUL_RETURN
Parameters
xoldMatrix entry to be normalised.
yoldMatrix entry to be annihilated.
xnewOutput: Normalised matrix entry.
ynewOutput: Annihilated matrix entry.
cOutput: Cosine entry of Givens matrix.
sOutput: Sine entry of Givens matrix.
returnValue QProblemB::copy ( const QProblemB rhs)
protected

Copies all members from given rhs object.

Returns
SUCCESSFUL_RETURN
Parameters
rhsRhs object.
returnValue QProblemB::copy ( const QProblemB rhs)
protected

Copies all members from given rhs object.

Returns
SUCCESSFUL_RETURN
Parameters
rhsRhs object.

Definition at line 1209 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

SymSparseMat * QProblemB::createDiagSparseMat ( int_t  n,
real_t  diagVal = 1.0 
)
protected

Creates a sparse diagonal (square-)matrix which is a given multiple of the identity matrix.

Returns
Diagonal matrix
Parameters
nRow/column dimension of matrix to be created.
diagValValue of all diagonal entries.

Definition at line 2032 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::determineDataShift ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
real_t *const  delta_g,
real_t *const  delta_lb,
real_t *const  delta_ub,
BooleanType Delta_bB_isZero 
)
protected

Determines step direction of the shift of the QP data.

Returns
SUCCESSFUL_RETURN
Parameters
g_newNew gradient vector.
lb_newNew lower bounds.
ub_newNew upper bounds.
delta_gOutput: Step direction of gradient vector.
delta_lbOutput: Step direction of lower bounds.
delta_ubOutput: Step direction of upper bounds.
Delta_bB_isZeroOutput: Indicates if active bounds are to be shifted.
returnValue QProblemB::determineDataShift ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
real_t *const  delta_g,
real_t *const  delta_lb,
real_t *const  delta_ub,
BooleanType Delta_bB_isZero 
)
protected

Determines step direction of the shift of the QP data.

Returns
SUCCESSFUL_RETURN
Parameters
g_newNew gradient vector.
lb_newNew lower bounds.
ub_newNew upper bounds.
delta_gOutput: Step direction of gradient vector.
delta_lbOutput: Step direction of lower bounds.
delta_ubOutput: Step direction of upper bounds.
Delta_bB_isZeroOutput: Indicates if active bounds are to be shifted.

Definition at line 1724 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::determineHessianType ( )
protected

If Hessian type has been set by the user, nothing is done. Otherwise the Hessian type is set to HST_IDENTITY, HST_ZERO, or HST_POSDEF (default), respectively.

Returns
SUCCESSFUL_RETURN
RET_HESSIAN_INDEFINITE
returnValue QProblemB::determineHessianType ( )
protected

If Hessian type has been set by the user, nothing is done. Otherwise the Hessian type is set to HST_IDENTITY, HST_ZERO, or HST_POSDEF (default), respectively.

Returns
SUCCESSFUL_RETURN
RET_HESSIAN_INDEFINITE

Definition at line 1302 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::determineStepDirection ( const real_t *const  delta_g,
const real_t *const  delta_lb,
const real_t *const  delta_ub,
BooleanType  Delta_bB_isZero,
real_t *const  delta_xFX,
real_t *const  delta_xFR,
real_t *const  delta_yFX 
)
private

Determines step direction of the homotopy path.

Returns
SUCCESSFUL_RETURN
RET_STEPDIRECTION_FAILED_CHOLESKY
Parameters
delta_gStep direction of gradient vector.
delta_lbStep direction of lower bounds.
delta_ubStep direction of upper bounds.
Delta_bB_isZeroIndicates if active bounds are to be shifted.
delta_xFXOutput: Primal homotopy step direction of fixed variables.
delta_xFROutput: Primal homotopy step direction of free variables.
delta_yFXOutput: Dual homotopy step direction of fixed variables' multiplier.
returnValue QProblemB::determineStepDirection ( const real_t *const  delta_g,
const real_t *const  delta_lb,
const real_t *const  delta_ub,
BooleanType  Delta_bB_isZero,
real_t *const  delta_xFX,
real_t *const  delta_xFR,
real_t *const  delta_yFX 
)
private

Determines step direction of the homotopy path.

Returns
SUCCESSFUL_RETURN
RET_STEPDIRECTION_FAILED_CHOLESKY
Parameters
delta_gStep direction of gradient vector.
delta_lbStep direction of lower bounds.
delta_ubStep direction of upper bounds.
Delta_bB_isZeroIndicates if active bounds are to be shifted.
delta_xFXOutput: Primal homotopy step direction of fixed variables.
delta_xFROutput: Primal homotopy step direction of free variables.
delta_yFXOutput: Dual homotopy step direction of fixed variables' multiplier.

Definition at line 2958 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::getBounds ( Bounds *const  _bounds) const
inline

Returns current bounds object of the QP (deep copy).

Returns
SUCCESSFUL_RETURN
Parameters
_boundsOutput: Bounds object.
returnValue QProblemB::getBounds ( Bounds *const  _bounds) const
inline

Returns current bounds object of the QP (deep copy).

Returns
SUCCESSFUL_RETURN
Parameters
_boundsOutput: Bounds object.
returnValue QProblemB::getBounds ( Bounds _bounds) const
inline

Returns current bounds object of the QP (deep copy).

Returns
SUCCESSFUL_RETURN
RET_QPOBJECT_NOT_SETUP
Parameters
_boundsOutput: Bounds object.
returnValue QProblemB::getBounds ( Bounds _bounds) const
inline

Returns current bounds object of the QP (deep copy).

Returns
SUCCESSFUL_RETURN
RET_QPOBJECT_NOT_SETUP
Parameters
_boundsOutput: Bounds object.
uint_t QProblemB::getCount ( ) const
inline

Returns the current number of QP problems solved.

Returns
Number of QP problems solved.
returnValue QProblemB::getDualSolution ( real_t *const  yOpt) const

Returns the dual solution vector.

Returns
SUCCESSFUL_RETURN
RET_QP_NOT_SOLVED
Parameters
yOptOutput: Dual solution vector (if QP has been solved).

Definition at line 563 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::getDualSolution ( real_t *const  yOpt) const

Returns the dual solution vector.

Returns
SUCCESSFUL_RETURN
RET_QP_NOT_SOLVED
Parameters
yOptOutput: Dual solution vector (if QP has been solved).
virtual returnValue QProblemB::getDualSolution ( real_t *const  yOpt) const
virtual

Returns the dual solution vector.

Returns
SUCCESSFUL_RETURN
RET_QP_NOT_SOLVED
Parameters
yOptOutput: Dual solution vector (if QP has been solved).

Reimplemented in QProblem, QProblem, QProblem, and QProblem.

virtual returnValue QProblemB::getDualSolution ( real_t *const  yOpt) const
virtual

Returns the dual solution vector.

Returns
SUCCESSFUL_RETURN
RET_QP_NOT_SOLVED
Parameters
yOptOutput: Dual solution vector (if QP has been solved).

Reimplemented in QProblem, QProblem, QProblem, and QProblem.

returnValue QProblemB::getG ( real_t *const  _g) const
inline

Returns gradient vector of the QP (deep copy).

Returns
SUCCESSFUL_RETURN
Parameters
_gArray of appropriate dimension for copying gradient vector.
returnValue QProblemB::getG ( real_t *const  _g) const
inline

Returns gradient vector of the QP (deep copy).

Returns
SUCCESSFUL_RETURN
Parameters
_gArray of appropriate dimension for copying gradient vector.
returnValue QProblemB::getH ( real_t *const  _H) const
inline

Returns Hessian matrix of the QP (deep copy).

Returns
SUCCESSFUL_RETURN
Parameters
_HArray of appropriate dimension for copying Hessian matrix.
returnValue QProblemB::getH ( real_t *const  _H) const
inline

Returns Hessian matrix of the QP (deep copy).

Returns
SUCCESSFUL_RETURN
Parameters
_HArray of appropriate dimension for copying Hessian matrix.
HessianType QProblemB::getHessianType ( ) const
inline

Returns Hessian type flag (type is not determined due to this call!).

Returns
Hessian type.
HessianType QProblemB::getHessianType ( ) const
inline

Returns Hessian type flag (type is not determined due to this call!).

Returns
Hessian type.
HessianType QProblemB::getHessianType ( ) const
inline

Returns Hessian type flag (type is not determined due to this call!).

Returns
Hessian type.
HessianType QProblemB::getHessianType ( ) const
inline

Returns Hessian type flag (type is not determined due to this call!).

Returns
Hessian type.
returnValue QProblemB::getLB ( real_t *const  _lb) const
inline

Returns lower bound vector of the QP (deep copy).

Returns
SUCCESSFUL_RETURN
Parameters
_lbArray of appropriate dimension for copying lower bound vector.
returnValue QProblemB::getLB ( int  number,
real_t value 
) const
inline

Returns single entry of lower bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INDEX_OUT_OF_BOUNDS
Parameters
numberNumber of entry to be returned.
valueOutput: lb[number].
returnValue QProblemB::getLB ( real_t *const  _lb) const
inline

Returns lower bound vector of the QP (deep copy).

Returns
SUCCESSFUL_RETURN
Parameters
_lbArray of appropriate dimension for copying lower bound vector.
returnValue QProblemB::getLB ( int  number,
real_t value 
) const
inline

Returns single entry of lower bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INDEX_OUT_OF_BOUNDS
Parameters
numberNumber of entry to be returned.
valueOutput: lb[number].
int QProblemB::getNFR ( )
inline

Returns the number of free variables.

Returns
Number of free variables.
int QProblemB::getNFR ( )
inline

Returns the number of free variables.

Returns
Number of free variables.
int_t QProblemB::getNFR ( ) const
inline

Returns the number of free variables.

Returns
Number of free variables.
int QProblemB::getNFR ( ) const
inline

Returns the number of free variables.

Returns
Number of free variables.
int QProblemB::getNFV ( ) const
inline

Returns the number of implicitly fixed variables.

Returns
Number of implicitly fixed variables.
int QProblemB::getNFV ( ) const
inline

Returns the number of implicitly fixed variables.

Returns
Number of implicitly fixed variables.
int_t QProblemB::getNFV ( ) const
inline

Returns the number of implicitly fixed variables.

Returns
Number of implicitly fixed variables.
int QProblemB::getNFV ( ) const
inline

Returns the number of implicitly fixed variables.

Returns
Number of implicitly fixed variables.
int QProblemB::getNFX ( )
inline

Returns the number of fixed variables.

Returns
Number of fixed variables.
int QProblemB::getNFX ( )
inline

Returns the number of fixed variables.

Returns
Number of fixed variables.
int_t QProblemB::getNFX ( ) const
inline

Returns the number of fixed variables.

Returns
Number of fixed variables.
int QProblemB::getNFX ( ) const
inline

Returns the number of fixed variables.

Returns
Number of fixed variables.
int QProblemB::getNV ( ) const
inline

Returns the number of variables.

Returns
Number of variables.
int QProblemB::getNV ( ) const
inline

Returns the number of variables.

Returns
Number of variables.
int_t QProblemB::getNV ( ) const
inline

Returns the number of variables.

Returns
Number of variables.
int QProblemB::getNV ( ) const
inline

Returns the number of variables.

Returns
Number of variables.
int QProblemB::getNZ ( )

Returns the dimension of null space.

Returns
Dimension of null space.

Definition at line 482 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

int QProblemB::getNZ ( )

Returns the dimension of null space.

Returns
Dimension of null space.
virtual int_t QProblemB::getNZ ( ) const
virtual

Returns the dimension of null space.

Returns
Dimension of null space.

Reimplemented in QProblem, and QProblem.

int_t QProblemB::getNZ ( ) const
virtual

Returns the dimension of null space.

Returns
Dimension of null space.

Reimplemented in QProblem, and QProblem.

Definition at line 828 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

real_t QProblemB::getObjVal ( ) const

Returns the optimal objective function value.

Returns
finite value: Optimal objective function value (QP was solved)
+infinity: QP was not yet solved

Definition at line 492 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

real_t QProblemB::getObjVal ( const real_t *const  _x) const

Returns the objective function value at an arbitrary point x.

Returns
Objective function value at point x
Parameters
_xPoint at which the objective function shall be evaluated.

Definition at line 516 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

real_t QProblemB::getObjVal ( ) const

Returns the optimal objective function value.

Returns
finite value: Optimal objective function value (QP was solved)
+infinity: QP was not yet solved
real_t QProblemB::getObjVal ( const real_t *const  _x) const

Returns the objective function value at an arbitrary point x.

Returns
Objective function value at point x
Parameters
_xPoint at which the objective function shall be evaluated.
real_t QProblemB::getObjVal ( ) const

Returns the optimal objective function value.

Returns
finite value: Optimal objective function value (QP was solved)
+infinity: QP was not yet solved
real_t QProblemB::getObjVal ( const real_t *const  _x) const

Returns the objective function value at an arbitrary point x.

Returns
Objective function value at point x
Parameters
_xPoint at which the objective function shall be evaluated.
real_t QProblemB::getObjVal ( ) const

Returns the optimal objective function value.

Returns
finite value: Optimal objective function value (QP was solved)
+infinity: QP was not yet solved
real_t QProblemB::getObjVal ( const real_t *const  _x) const

Returns the objective function value at an arbitrary point x.

Returns
Objective function value at point x
Parameters
_xPoint at which the objective function shall be evaluated.
Options QProblemB::getOptions ( ) const
inline

Returns current options struct.

Returns
Current options struct.
Options QProblemB::getOptions ( ) const
inline

Returns current options struct.

Returns
Current options struct.
returnValue QProblemB::getPrimalSolution ( real_t *const  xOpt) const

Returns the primal solution vector.

Returns
SUCCESSFUL_RETURN
RET_QP_NOT_SOLVED
Parameters
xOptOutput: Primal solution vector (if QP has been solved).

Definition at line 538 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::getPrimalSolution ( real_t *const  xOpt) const

Returns the primal solution vector.

Returns
SUCCESSFUL_RETURN
RET_QP_NOT_SOLVED
Parameters
xOptOutput: Primal solution vector (if QP has been solved).
returnValue QProblemB::getPrimalSolution ( real_t *const  xOpt) const

Returns the primal solution vector.

Returns
SUCCESSFUL_RETURN
RET_QP_NOT_SOLVED
Parameters
xOptOutput: Primal solution vector (if QP has been solved).
returnValue QProblemB::getPrimalSolution ( real_t *const  xOpt) const

Returns the primal solution vector.

Returns
SUCCESSFUL_RETURN
RET_QP_NOT_SOLVED
Parameters
xOptOutput: Primal solution vector (if QP has been solved).
PrintLevel QProblemB::getPrintLevel ( ) const
inline

Returns the print level.

Returns
Print level.
PrintLevel QProblemB::getPrintLevel ( ) const
inline

Returns the print level.

Returns
Print level.
PrintLevel QProblemB::getPrintLevel ( ) const
inline

Returns the print level.

Returns
Print level.
PrintLevel QProblemB::getPrintLevel ( ) const
inline

Returns the print level.

Returns
Print level.
real_t QProblemB::getRelativeHomotopyLength ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new 
)
protected

Compute relative length of homotopy in data space for termination criterion.

Returns
Relative length in data space.
Parameters
g_newFinal gradient.
lb_newFinal lower variable bounds.
ub_newFinal upper variable bounds.

Definition at line 2107 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

QProblemStatus QProblemB::getStatus ( ) const
inline

Returns status of the solution process.

Returns
Status of solution process.
QProblemStatus QProblemB::getStatus ( ) const
inline

Returns status of the solution process.

Returns
Status of solution process.
QProblemStatus QProblemB::getStatus ( ) const
inline

Returns status of the solution process.

Returns
Status of solution process.
QProblemStatus QProblemB::getStatus ( ) const
inline

Returns status of the solution process.

Returns
Status of solution process.
returnValue QProblemB::getUB ( real_t *const  _ub) const
inline

Returns upper bound vector of the QP (deep copy).

Returns
SUCCESSFUL_RETURN
Parameters
_ubArray of appropriate dimension for copying upper bound vector.
returnValue QProblemB::getUB ( int  number,
real_t value 
) const
inline

Returns single entry of upper bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INDEX_OUT_OF_BOUNDS
Parameters
numberNumber of entry to be returned.
valueOutput: ub[number].
returnValue QProblemB::getUB ( real_t *const  _ub) const
inline

Returns upper bound vector of the QP (deep copy).

Returns
SUCCESSFUL_RETURN
Parameters
_ubArray of appropriate dimension for copying upper bound vector.
returnValue QProblemB::getUB ( int  number,
real_t value 
) const
inline

Returns single entry of upper bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INDEX_OUT_OF_BOUNDS
Parameters
numberNumber of entry to be returned.
valueOutput: ub[number].
returnValue QProblemB::getWorkingSet ( real_t workingSet)
virtual

Writes a vector with the state of the working set

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
Parameters
workingSetOutput: array containing state of the working set.

Reimplemented in QProblem.

Definition at line 638 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::getWorkingSetBounds ( real_t workingSetB)
virtual

Writes a vector with the state of the working set of bounds

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
Parameters
workingSetBOutput: array containing state of the working set of bounds.

Reimplemented in QProblem.

Definition at line 647 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::getWorkingSetConstraints ( real_t workingSetC)
virtual

Writes a vector with the state of the working set of constraints

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
Parameters
workingSetCOutput: array containing state of the working set of constraints.

Reimplemented in QProblem.

Definition at line 672 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::hotstart ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
int &  nWSR,
real_t *const  cputime 
)

Solves an initialised QProblemB using online active set strategy.

Returns
SUCCESSFUL_RETURN
RET_MAX_NWSR_REACHED
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED
RET_HOTSTART_FAILED
RET_SHIFT_DETERMINATION_FAILED
RET_STEPDIRECTION_DETERMINATION_FAILED
RET_STEPLENGTH_DETERMINATION_FAILED
RET_HOMOTOPY_STEP_FAILED
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_HOTSTART_STOPPED_UNBOUNDEDNESS
RET_INACCURATE_SOLUTION
RET_NO_SOLUTION
Parameters
g_newGradient of neighbouring QP to be solved.
lb_newLower bounds of neighbouring QP to be solved.
If no lower bounds exist, a NULL pointer can be passed.
ub_newUpper bounds of neighbouring QP to be solved.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeOutput: CPU time required to solve QP (or to perform nWSR iterations).

Definition at line 285 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::hotstart ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
int &  nWSR,
real_t *const  cputime 
)

Solves an initialised QProblemB using online active set strategy.

Returns
SUCCESSFUL_RETURN
RET_MAX_NWSR_REACHED
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED
RET_HOTSTART_FAILED
RET_SHIFT_DETERMINATION_FAILED
RET_STEPDIRECTION_DETERMINATION_FAILED
RET_STEPLENGTH_DETERMINATION_FAILED
RET_HOMOTOPY_STEP_FAILED
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_HOTSTART_STOPPED_UNBOUNDEDNESS
RET_INACCURATE_SOLUTION
RET_NO_SOLUTION
Parameters
g_newGradient of neighbouring QP to be solved.
lb_newLower bounds of neighbouring QP to be solved.
If no lower bounds exist, a NULL pointer can be passed.
ub_newUpper bounds of neighbouring QP to be solved.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeOutput: CPU time required to solve QP (or to perform nWSR iterations).
returnValue QProblemB::hotstart ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
int_t nWSR,
real_t *const  cputime = 0,
const Bounds *const  guessedBounds = 0 
)

Solves an initialised QP sequence using the online active set strategy. By default, QP solution is started from previous solution. If a guess for the working set is provided, an initialised homotopy is performed.

Note: This function internally calls solveQP/solveRegularisedQP for solving an initialised QP!

Returns
SUCCESSFUL_RETURN
RET_MAX_NWSR_REACHED
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED
RET_HOTSTART_FAILED
RET_SHIFT_DETERMINATION_FAILED
RET_STEPDIRECTION_DETERMINATION_FAILED
RET_STEPLENGTH_DETERMINATION_FAILED
RET_HOMOTOPY_STEP_FAILED
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_HOTSTART_STOPPED_UNBOUNDEDNESS
RET_SETUP_AUXILIARYQP_FAILED
Parameters
g_newGradient of neighbouring QP to be solved.
lb_newLower bounds of neighbouring QP to be solved.
If no lower bounds exist, a NULL pointer can be passed.
ub_newUpper bounds of neighbouring QP to be solved.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP solution.
Output: CPU time spent for QP solution (or to perform nWSR iterations).
guessedBoundsOptimal working set of bounds for solution (xOpt,yOpt).
(If a null pointer is passed, the previous working set is kept!)
returnValue QProblemB::hotstart ( const char *const  g_file,
const char *const  lb_file,
const char *const  ub_file,
int_t nWSR,
real_t *const  cputime = 0,
const Bounds *const  guessedBounds = 0 
)

Solves an initialised QP sequence using the online active set strategy, where QP data is read from files. By default, QP solution is started from previous solution. If a guess for the working set is provided, an initialised homotopy is performed.

Note: This function internally calls solveQP/solveRegularisedQP for solving an initialised QP!

Returns
SUCCESSFUL_RETURN
RET_MAX_NWSR_REACHED
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED
RET_HOTSTART_FAILED
RET_SHIFT_DETERMINATION_FAILED
RET_STEPDIRECTION_DETERMINATION_FAILED
RET_STEPLENGTH_DETERMINATION_FAILED
RET_HOMOTOPY_STEP_FAILED
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_HOTSTART_STOPPED_UNBOUNDEDNESS
RET_UNABLE_TO_READ_FILE
RET_SETUP_AUXILIARYQP_FAILED
RET_INVALID_ARGUMENTS
Parameters
g_fileName of file where gradient, of neighbouring QP to be solved, is stored.
lb_fileName of file where lower bounds, of neighbouring QP to be solved, is stored.
If no lower bounds exist, a NULL pointer can be passed.
ub_fileName of file where upper bounds, of neighbouring QP to be solved, is stored.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP solution.
Output: CPU time spent for QP solution (or to perform nWSR iterations).
guessedBoundsOptimal working set of bounds for solution (xOpt,yOpt).
(If a null pointer is passed, the previous working set is kept!)
returnValue QProblemB::hotstart ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
int &  nWSR,
real_t *const  cputime 
)

Solves an initialised QProblemB using online active set strategy. Note: This function internally calls solveQP/solveRegularisedQP for solving an initialised QP!

Returns
SUCCESSFUL_RETURN
RET_MAX_NWSR_REACHED
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED
RET_HOTSTART_FAILED
RET_SHIFT_DETERMINATION_FAILED
RET_STEPDIRECTION_DETERMINATION_FAILED
RET_STEPLENGTH_DETERMINATION_FAILED
RET_HOMOTOPY_STEP_FAILED
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_HOTSTART_STOPPED_UNBOUNDEDNESS
Parameters
g_newGradient of neighbouring QP to be solved.
lb_newLower bounds of neighbouring QP to be solved.
If no lower bounds exist, a NULL pointer can be passed.
ub_newUpper bounds of neighbouring QP to be solved.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP solution.
Output: CPU time spend for QP solution (or to perform nWSR iterations).
returnValue QProblemB::hotstart ( const char *const  g_file,
const char *const  lb_file,
const char *const  ub_file,
int &  nWSR,
real_t *const  cputime 
)

Solves an initialised QProblemB online active set strategy reading QP data from files. Note: This function internally calls solveQP/solveRegularisedQP for solving an initialised QP!

Returns
SUCCESSFUL_RETURN
RET_MAX_NWSR_REACHED
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED
RET_HOTSTART_FAILED
RET_SHIFT_DETERMINATION_FAILED
RET_STEPDIRECTION_DETERMINATION_FAILED
RET_STEPLENGTH_DETERMINATION_FAILED
RET_HOMOTOPY_STEP_FAILED
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_HOTSTART_STOPPED_UNBOUNDEDNESS
RET_UNABLE_TO_READ_FILE
RET_INVALID_ARGUMENTS
Parameters
g_fileName of file where gradient, of neighbouring QP to be solved, is stored.
lb_fileName of file where lower bounds, of neighbouring QP to be solved, is stored.
If no lower bounds exist, a NULL pointer can be passed.
ub_fileName of file where upper bounds, of neighbouring QP to be solved, is stored.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP solution.
Output: CPU time spend for QP solution (or to perform nWSR iterations).

Definition at line 655 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::hotstart ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
int &  nWSR,
real_t *const  cputime,
const Bounds *const  guessedBounds 
)

Solves an initialised QProblemB using online active set strategy (using an initialised homotopy). Note: This function internally calls solveQP/solveRegularisedQP for solving an initialised QP!

Returns
SUCCESSFUL_RETURN
RET_MAX_NWSR_REACHED
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED
RET_HOTSTART_FAILED
RET_SHIFT_DETERMINATION_FAILED
RET_STEPDIRECTION_DETERMINATION_FAILED
RET_STEPLENGTH_DETERMINATION_FAILED
RET_HOMOTOPY_STEP_FAILED
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_HOTSTART_STOPPED_UNBOUNDEDNESS
RET_SETUP_AUXILIARYQP_FAILED
Parameters
g_newGradient of neighbouring QP to be solved.
lb_newLower bounds of neighbouring QP to be solved.
If no lower bounds exist, a NULL pointer can be passed.
ub_newUpper bounds of neighbouring QP to be solved.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP solution.
Output: CPU time spend for QP solution (or to perform nWSR iterations).
guessedBoundsInitial guess for working set of bounds. A null pointer corresponds to an empty working set!

Definition at line 713 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::hotstart ( const char *const  g_file,
const char *const  lb_file,
const char *const  ub_file,
int &  nWSR,
real_t *const  cputime,
const Bounds *const  guessedBounds 
)

Solves an initialised QProblemB using online active set strategy (using an initialised homotopy) reading QP data from files. Note: This function internally calls solveQP/solveRegularisedQP for solving an initialised QP!

Returns
SUCCESSFUL_RETURN
RET_MAX_NWSR_REACHED
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED
RET_HOTSTART_FAILED
RET_SHIFT_DETERMINATION_FAILED
RET_STEPDIRECTION_DETERMINATION_FAILED
RET_STEPLENGTH_DETERMINATION_FAILED
RET_HOMOTOPY_STEP_FAILED
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_HOTSTART_STOPPED_UNBOUNDEDNESS
RET_UNABLE_TO_READ_FILE
RET_INVALID_ARGUMENTS
RET_SETUP_AUXILIARYQP_FAILED
Parameters
g_fileName of file where gradient, of neighbouring QP to be solved, is stored.
lb_fileName of file where lower bounds, of neighbouring QP to be solved, is stored.
If no lower bounds exist, a NULL pointer can be passed.
ub_fileName of file where upper bounds, of neighbouring QP to be solved, is stored.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP solution.
Output: CPU time spend for QP solution (or to perform nWSR iterations).
guessedBoundsInitial guess for working set of bounds. A null pointer corresponds to an empty working set!

Definition at line 767 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::hotstart_determineDataShift ( const int *const  FX_idx,
const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
real_t *const  delta_g,
real_t *const  delta_lb,
real_t *const  delta_ub,
BooleanType Delta_bB_isZero 
)
protected

Determines step direction of the shift of the QP data.

Returns
SUCCESSFUL_RETURN
Parameters
FX_idxIndex array of fixed variables.
g_newNew gradient vector.
lb_newNew lower bounds.
ub_newNew upper bounds.
delta_gOutput: Step direction of gradient vector.
delta_lbOutput: Step direction of lower bounds.
delta_ubOutput: Step direction of upper bounds.
Delta_bB_isZeroOutput: Indicates if active bounds are to be shifted.

Definition at line 1427 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::hotstart_determineDataShift ( const int *const  FX_idx,
const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
real_t *const  delta_g,
real_t *const  delta_lb,
real_t *const  delta_ub,
BooleanType Delta_bB_isZero 
)
protected

Determines step direction of the shift of the QP data.

Returns
SUCCESSFUL_RETURN
Parameters
FX_idxIndex array of fixed variables.
g_newNew gradient vector.
lb_newNew lower bounds.
ub_newNew upper bounds.
delta_gOutput: Step direction of gradient vector.
delta_lbOutput: Step direction of lower bounds.
delta_ubOutput: Step direction of upper bounds.
Delta_bB_isZeroOutput: Indicates if active bounds are to be shifted.
returnValue QProblemB::hotstart_determineStepDirection ( const int *const  FR_idx,
const int *const  FX_idx,
const real_t *const  delta_g,
const real_t *const  delta_lb,
const real_t *const  delta_ub,
BooleanType  Delta_bB_isZero,
real_t *const  delta_xFX,
real_t *const  delta_xFR,
real_t *const  delta_yFX 
)
private

Determines step direction of the homotopy path.

Returns
SUCCESSFUL_RETURN
RET_STEPDIRECTION_FAILED_CHOLESKY
Parameters
FR_idxIndex array of free variables.
FX_idxIndex array of fixed variables.
delta_gStep direction of gradient vector.
delta_lbStep direction of lower bounds.
delta_ubStep direction of upper bounds.
Delta_bB_isZeroIndicates if active bounds are to be shifted.
delta_xFXOutput: Primal homotopy step direction of fixed variables.
delta_xFROutput: Primal homotopy step direction of free variables.
delta_yFXOutput: Dual homotopy step direction of fixed variables' multiplier.

Definition at line 1570 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::hotstart_determineStepDirection ( const int *const  FR_idx,
const int *const  FX_idx,
const real_t *const  delta_g,
const real_t *const  delta_lb,
const real_t *const  delta_ub,
BooleanType  Delta_bB_isZero,
real_t *const  delta_xFX,
real_t *const  delta_xFR,
real_t *const  delta_yFX 
)
private

Determines step direction of the homotopy path.

Returns
SUCCESSFUL_RETURN
RET_STEPDIRECTION_FAILED_CHOLESKY
Parameters
FR_idxIndex array of free variables.
FX_idxIndex array of fixed variables.
delta_gStep direction of gradient vector.
delta_lbStep direction of lower bounds.
delta_ubStep direction of upper bounds.
Delta_bB_isZeroIndicates if active bounds are to be shifted.
delta_xFXOutput: Primal homotopy step direction of fixed variables.
delta_xFROutput: Primal homotopy step direction of free variables.
delta_yFXOutput: Dual homotopy step direction of fixed variables' multiplier.
returnValue QProblemB::hotstart_determineStepLength ( const int *const  FR_idx,
const int *const  FX_idx,
const real_t *const  delta_lb,
const real_t *const  delta_ub,
const real_t *const  delta_xFR,
const real_t *const  delta_yFX,
int &  BC_idx,
SubjectToStatus BC_status 
)
private

Determines the maximum possible step length along the homotopy path.

Returns
SUCCESSFUL_RETURN
Parameters
FR_idxIndex array of free variables.
FX_idxIndex array of fixed variables.
delta_lbStep direction of lower bounds.
delta_ubStep direction of upper bounds.
delta_xFRPrimal homotopy step direction of free variables.
delta_yFXDual homotopy step direction of fixed variables' multiplier.
BC_idxOutput: Index of blocking constraint.
BC_statusOutput: Status of blocking constraint.

Definition at line 1686 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::hotstart_determineStepLength ( const int *const  FR_idx,
const int *const  FX_idx,
const real_t *const  delta_lb,
const real_t *const  delta_ub,
const real_t *const  delta_xFR,
const real_t *const  delta_yFX,
int &  BC_idx,
SubjectToStatus BC_status 
)
private

Determines the maximum possible step length along the homotopy path.

Returns
SUCCESSFUL_RETURN
Parameters
FR_idxIndex array of free variables.
FX_idxIndex array of fixed variables.
delta_lbStep direction of lower bounds.
delta_ubStep direction of upper bounds.
delta_xFRPrimal homotopy step direction of free variables.
delta_yFXDual homotopy step direction of fixed variables' multiplier.
BC_idxOutput: Index of blocking constraint.
BC_statusOutput: Status of blocking constraint.
returnValue QProblemB::hotstart_performStep ( const int *const  FR_idx,
const int *const  FX_idx,
const real_t *const  delta_g,
const real_t *const  delta_lb,
const real_t *const  delta_ub,
const real_t *const  delta_xFX,
const real_t *const  delta_xFR,
const real_t *const  delta_yFX,
int  BC_idx,
SubjectToStatus  BC_status 
)
private

Performs a step along the homotopy path (and updates active set).

Returns
SUCCESSFUL_RETURN
RET_OPTIMAL_SOLUTION_FOUND
RET_REMOVE_FROM_ACTIVESET_FAILED
RET_ADD_TO_ACTIVESET_FAILED
RET_QP_INFEASIBLE
Parameters
FR_idxIndex array of free variables.
FX_idxIndex array of fixed variables.
delta_gStep direction of gradient vector.
delta_lbStep direction of lower bounds.
delta_ubStep direction of upper bounds.
delta_xFXPrimal homotopy step direction of fixed variables.
delta_xFRPrimal homotopy step direction of free variables.
delta_yFXDual homotopy step direction of fixed variables' multiplier.
BC_idxIndex of blocking constraint.
BC_statusStatus of blocking constraint.

Definition at line 1837 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::hotstart_performStep ( const int *const  FR_idx,
const int *const  FX_idx,
const real_t *const  delta_g,
const real_t *const  delta_lb,
const real_t *const  delta_ub,
const real_t *const  delta_xFX,
const real_t *const  delta_xFR,
const real_t *const  delta_yFX,
int  BC_idx,
SubjectToStatus  BC_status 
)
private

Performs a step along the homotopy path (and updates active set).

Returns
SUCCESSFUL_RETURN
RET_OPTIMAL_SOLUTION_FOUND
RET_REMOVE_FROM_ACTIVESET_FAILED
RET_ADD_TO_ACTIVESET_FAILED
RET_QP_INFEASIBLE
Parameters
FR_idxIndex array of free variables.
FX_idxIndex array of fixed variables.
delta_gStep direction of gradient vector.
delta_lbStep direction of lower bounds.
delta_ubStep direction of upper bounds.
delta_xFXPrimal homotopy step direction of fixed variables.
delta_xFRPrimal homotopy step direction of free variables.
delta_yFXDual homotopy step direction of fixed variables' multiplier.
BC_idxIndex of blocking constraint.
BC_statusStatus of blocking constraint.
returnValue QProblemB::init ( const real_t *const  _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub,
int &  nWSR,
const real_t *const  yOpt = 0,
real_t *const  cputime = 0 
)

Initialises a QProblemB with given QP data and solves it using an initial homotopy with empty working set (at most nWSR iterations).

Returns
SUCCESSFUL_RETURN
RET_INIT_FAILED
RET_INIT_FAILED_CHOLESKY
RET_INIT_FAILED_HOTSTART
RET_INIT_FAILED_INFEASIBILITY
RET_INIT_FAILED_UNBOUNDEDNESS
RET_MAX_NWSR_REACHED
RET_INVALID_ARGUMENTS
RET_INACCURATE_SOLUTION
RET_NO_SOLUTION
Parameters
_HHessian matrix.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations when using initial homotopy.
Output: Number of performed working set recalculations.
yOptInitial guess for dual solution vector.
cputimeOutput: CPU time required to initialise QP.

Definition at line 268 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::init ( const real_t *const  _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub,
int &  nWSR,
const real_t *const  yOpt = 0,
real_t *const  cputime = 0 
)

Initialises a QProblemB with given QP data and solves it using an initial homotopy with empty working set (at most nWSR iterations).

Returns
SUCCESSFUL_RETURN
RET_INIT_FAILED
RET_INIT_FAILED_CHOLESKY
RET_INIT_FAILED_HOTSTART
RET_INIT_FAILED_INFEASIBILITY
RET_INIT_FAILED_UNBOUNDEDNESS
RET_MAX_NWSR_REACHED
RET_INVALID_ARGUMENTS
RET_INACCURATE_SOLUTION
RET_NO_SOLUTION
Parameters
_HHessian matrix.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations when using initial homotopy.
Output: Number of performed working set recalculations.
yOptInitial guess for dual solution vector.
cputimeOutput: CPU time required to initialise QP.
returnValue QProblemB::init ( SymmetricMatrix _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub,
int &  nWSR,
real_t *const  cputime 
)

Initialises a QProblemB with given QP data and solves it using an initial homotopy with empty working set (at most nWSR iterations). Note: This function internally calls solveInitialQP for initialisation!

Returns
SUCCESSFUL_RETURN
RET_INIT_FAILED
RET_INIT_FAILED_CHOLESKY
RET_INIT_FAILED_HOTSTART
RET_INIT_FAILED_INFEASIBILITY
RET_INIT_FAILED_UNBOUNDEDNESS
RET_MAX_NWSR_REACHED
RET_INVALID_ARGUMENTS
Parameters
_HHessian matrix.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations when using initial homotopy.
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP initialisation.
Output: CPU time spend for QP initialisation.

Definition at line 228 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::init ( SymmetricMatrix _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub,
int_t nWSR,
real_t *const  cputime = 0,
const real_t *const  xOpt = 0,
const real_t *const  yOpt = 0,
const Bounds *const  guessedBounds = 0,
const real_t *const  _R = 0 
)

Initialises a simply bounded QP problem with given QP data and tries to solve it using at most nWSR iterations. Depending on the parameter constellation it:

  1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB empty (or all implicit equality bounds),
  2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB by "clipping",
  3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB from yOpt != 0,
  4. 0, 0, gB: starts with xOpt = 0, yOpt = 0 and gB,
  5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB from yOpt != 0,
  6. xOpt, 0, gB: starts with xOpt, yOpt = 0 and gB,
  7. xOpt, yOpt, gB: starts with xOpt, yOpt and gB (assume them to be consistent!)

Note: This function internally calls solveInitialQP for initialisation!

\return SUCCESSFUL_RETURN \n
            RET_INIT_FAILED \n
            RET_INIT_FAILED_CHOLESKY \n
            RET_INIT_FAILED_HOTSTART \n
            RET_INIT_FAILED_INFEASIBILITY \n
            RET_INIT_FAILED_UNBOUNDEDNESS \n
            RET_MAX_NWSR_REACHED \n
            RET_INVALID_ARGUMENTS  
Parameters
_HHessian matrix (a shallow copy is made).
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations when using initial homotopy.
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP initialisation.
Output: CPU time spent for QP initialisation (if pointer passed).
xOptOptimal primal solution vector. A NULL pointer can be passed.
(If a null pointer is passed, the old primal solution is kept!)
yOptOptimal dual solution vector. A NULL pointer can be passed.
(If a null pointer is passed, the old dual solution is kept!)
guessedBoundsOptimal working set of bounds for solution (xOpt,yOpt).
(If a null pointer is passed, all bounds are assumed inactive!)
_RPre-computed (upper triangular) Cholesky factor of Hessian matrix. The Cholesky factor must be stored in a real_t array of size nV*nV in row-major format. Note: Only used if xOpt/yOpt and gB are NULL!
(If a null pointer is passed, Cholesky decomposition is computed internally!)

Definition at line 247 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::init ( const real_t *const  _H,
const real_t *const  _R,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub,
int &  nWSR,
const real_t *const  yOpt = 0,
real_t *const  cputime = 0 
)

Initialises a QProblemB with given QP data and solves it using an initial homotopy with empty working set (at most nWSR iterations).

Returns
SUCCESSFUL_RETURN
RET_INIT_FAILED
RET_INIT_FAILED_CHOLESKY
RET_INIT_FAILED_HOTSTART
RET_INIT_FAILED_INFEASIBILITY
RET_INIT_FAILED_UNBOUNDEDNESS
RET_MAX_NWSR_REACHED
RET_INVALID_ARGUMENTS
RET_INACCURATE_SOLUTION
RET_NO_SOLUTION
Parameters
_HHessian matrix.
_RCholesky factorization of the Hessian matrix.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations when using initial homotopy.
Output: Number of performed working set recalculations.
yOptInitial guess for dual solution vector.
cputimeOutput: CPU time required to initialise QP.

Definition at line 298 of file external_packages/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::init ( const real_t *const  _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub,
int &  nWSR,
real_t *const  cputime 
)

Initialises a QProblemB with given QP data and solves it using an initial homotopy with empty working set (at most nWSR iterations). Note: This function internally calls solveInitialQP for initialisation!

Returns
SUCCESSFUL_RETURN
RET_INIT_FAILED
RET_INIT_FAILED_CHOLESKY
RET_INIT_FAILED_HOTSTART
RET_INIT_FAILED_INFEASIBILITY
RET_INIT_FAILED_UNBOUNDEDNESS
RET_MAX_NWSR_REACHED
RET_INVALID_ARGUMENTS
Parameters
_HHessian matrix.
If Hessian matrix is trivial, a NULL pointer can be passed.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations when using initial homotopy.
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP initialisation.
Output: CPU time spend for QP initialisation.

Definition at line 255 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::init ( const char *const  H_file,
const char *const  g_file,
const char *const  lb_file,
const char *const  ub_file,
int &  nWSR,
real_t *const  cputime 
)

Initialises a QProblemB with given QP data to be read from files and solves it using an initial homotopy with empty working set (at most nWSR iterations). Note: This function internally calls solveInitialQP for initialisation!

Returns
SUCCESSFUL_RETURN
RET_INIT_FAILED
RET_INIT_FAILED_CHOLESKY
RET_INIT_FAILED_HOTSTART
RET_INIT_FAILED_INFEASIBILITY
RET_INIT_FAILED_UNBOUNDEDNESS
RET_MAX_NWSR_REACHED
RET_UNABLE_TO_READ_FILE
Parameters
H_fileName of file where Hessian matrix is stored.
If Hessian matrix is trivial, a NULL pointer can be passed.
g_fileName of file where gradient vector is stored.
lb_fileName of file where lower bound vector.
If no lower bounds exist, a NULL pointer can be passed.
ub_fileName of file where upper bound vector.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations when using initial homotopy.
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP initialisation.
Output: CPU time spend for QP initialisation.

Definition at line 282 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::init ( const real_t *const  _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub,
int_t nWSR,
real_t *const  cputime = 0,
const real_t *const  xOpt = 0,
const real_t *const  yOpt = 0,
const Bounds *const  guessedBounds = 0,
const real_t *const  _R = 0 
)

Initialises a simply bounded QP problem with given QP data and tries to solve it using at most nWSR iterations. Depending on the parameter constellation it:

  1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB empty (or all implicit equality bounds),
  2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB by "clipping",
  3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB from yOpt != 0,
  4. 0, 0, gB: starts with xOpt = 0, yOpt = 0 and gB,
  5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB from yOpt != 0,
  6. xOpt, 0, gB: starts with xOpt, yOpt = 0 and gB,
  7. xOpt, yOpt, gB: starts with xOpt, yOpt and gB (assume them to be consistent!)

Note: This function internally calls solveInitialQP for initialisation!

\return SUCCESSFUL_RETURN \n
            RET_INIT_FAILED \n
            RET_INIT_FAILED_CHOLESKY \n
            RET_INIT_FAILED_HOTSTART \n
            RET_INIT_FAILED_INFEASIBILITY \n
            RET_INIT_FAILED_UNBOUNDEDNESS \n
            RET_MAX_NWSR_REACHED \n
            RET_INVALID_ARGUMENTS  
Parameters
_HHessian matrix (a shallow copy is made).
If Hessian matrix is trivial, a NULL pointer can be passed.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations when using initial homotopy.
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP initialisation.
Output: CPU time spent for QP initialisation (if pointer passed).
xOptOptimal primal solution vector. A NULL pointer can be passed.
(If a null pointer is passed, the old primal solution is kept!)
yOptOptimal dual solution vector. A NULL pointer can be passed.
(If a null pointer is passed, the old dual solution is kept!)
guessedBoundsOptimal working set of bounds for solution (xOpt,yOpt).
(If a null pointer is passed, all bounds are assumed inactive!)
_RPre-computed (upper triangular) Cholesky factor of Hessian matrix. The Cholesky factor must be stored in a real_t array of size nV*nV in row-major format. Note: Only used if xOpt/yOpt and gB are NULL!
(If a null pointer is passed, Cholesky decomposition is computed internally!)

Definition at line 296 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::init ( SymmetricMatrix _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub,
int &  nWSR,
real_t *const  cputime,
const real_t *const  xOpt,
const real_t *const  yOpt,
const Bounds *const  guessedBounds 
)

Initialises a QProblemB with given QP data and solves it depending on the parameter constellation:

  1. 0, 0, 0 : start with xOpt = 0, yOpt = 0 and IB empty (or all implicit equality bounds),
  2. xOpt, 0, 0 : start with xOpt, yOpt = 0 and obtain IB by "clipping",
  3. 0, yOpt, 0 : start with xOpt = 0, yOpt and obtain IB from yOpt != 0,
  4. 0, 0, IB: start with xOpt = 0, yOpt = 0 and IB,
  5. xOpt, yOpt, 0 : start with xOpt, yOpt and obtain IB from yOpt != 0,
  6. xOpt, 0, IB: start with xOpt, yOpt = 0 and IB,
  7. xOpt, yOpt, IB: start with xOpt, yOpt and IB (assume them to be consistent!) Note: This function internally calls solveInitialQP for initialisation!
    Returns
    SUCCESSFUL_RETURN
    RET_INIT_FAILED
    RET_INIT_FAILED_CHOLESKY
    RET_INIT_FAILED_HOTSTART
    RET_INIT_FAILED_INFEASIBILITY
    RET_INIT_FAILED_UNBOUNDEDNESS
    RET_MAX_NWSR_REACHED
    RET_INVALID_ARGUMENTS
Parameters
_HHessian matrix.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations when using initial homotopy.
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP initialisation.
Output: CPU time spend for QP initialisation.
xOptOptimal primal solution vector. A NULL pointer can be passed.
yOptOptimal dual solution vector. A NULL pointer can be passed.
guessedBoundsOptimal working set for solution (xOpt,yOpt). A NULL pointer can be passed.

Definition at line 309 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::init ( const char *const  H_file,
const char *const  g_file,
const char *const  lb_file,
const char *const  ub_file,
int_t nWSR,
real_t *const  cputime = 0,
const real_t *const  xOpt = 0,
const real_t *const  yOpt = 0,
const Bounds *const  guessedBounds = 0,
const char *const  R_file = 0 
)

Initialises a simply bounded QP problem with given QP data to be read from files and solves it using at most nWSR iterations. Depending on the parameter constellation it:

  1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB empty (or all implicit equality bounds),
  2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB by "clipping",
  3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB from yOpt != 0,
  4. 0, 0, gB: starts with xOpt = 0, yOpt = 0 and gB,
  5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB from yOpt != 0,
  6. xOpt, 0, gB: starts with xOpt, yOpt = 0 and gB,
  7. xOpt, yOpt, gB: starts with xOpt, yOpt and gB (assume them to be consistent!)

Note: This function internally calls solveInitialQP for initialisation!

\return SUCCESSFUL_RETURN \n
            RET_INIT_FAILED \n
            RET_INIT_FAILED_CHOLESKY \n
            RET_INIT_FAILED_HOTSTART \n
            RET_INIT_FAILED_INFEASIBILITY \n
            RET_INIT_FAILED_UNBOUNDEDNESS \n
            RET_MAX_NWSR_REACHED \n
            RET_UNABLE_TO_READ_FILE  
Parameters
H_fileName of file where Hessian matrix is stored.
If Hessian matrix is trivial, a NULL pointer can be passed.
g_fileName of file where gradient vector is stored.
lb_fileName of file where lower bound vector.
If no lower bounds exist, a NULL pointer can be passed.
ub_fileName of file where upper bound vector.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations when using initial homotopy.
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP initialisation.
Output: CPU time spent for QP initialisation (if pointer passed).
xOptOptimal primal solution vector. A NULL pointer can be passed.
(If a null pointer is passed, the old primal solution is kept!)
yOptOptimal dual solution vector. A NULL pointer can be passed.
(If a null pointer is passed, the old dual solution is kept!)
guessedBoundsOptimal working set of bounds for solution (xOpt,yOpt).
(If a null pointer is passed, all bounds are assumed inactive!)
R_fileName of the file where a pre-computed (upper triangular) Cholesky factor of the Hessian matrix is stored.
(If a null pointer is passed, Cholesky decomposition is computed internally!)

Definition at line 345 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::init ( const real_t *const  _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub,
int &  nWSR,
real_t *const  cputime,
const real_t *const  xOpt,
const real_t *const  yOpt,
const Bounds *const  guessedBounds 
)

Initialises a QProblemB with given QP data and solves it depending on the parameter constellation:

  1. 0, 0, 0 : start with xOpt = 0, yOpt = 0 and IB empty (or all implicit equality bounds),
  2. xOpt, 0, 0 : start with xOpt, yOpt = 0 and obtain IB by "clipping",
  3. 0, yOpt, 0 : start with xOpt = 0, yOpt and obtain IB from yOpt != 0,
  4. 0, 0, IB: start with xOpt = 0, yOpt = 0 and IB,
  5. xOpt, yOpt, 0 : start with xOpt, yOpt and obtain IB from yOpt != 0,
  6. xOpt, 0, IB: start with xOpt, yOpt = 0 and IB,
  7. xOpt, yOpt, IB: start with xOpt, yOpt and IB (assume them to be consistent!) Note: This function internally calls solveInitialQP for initialisation!
    Returns
    SUCCESSFUL_RETURN
    RET_INIT_FAILED
    RET_INIT_FAILED_CHOLESKY
    RET_INIT_FAILED_HOTSTART
    RET_INIT_FAILED_INFEASIBILITY
    RET_INIT_FAILED_UNBOUNDEDNESS
    RET_MAX_NWSR_REACHED
    RET_INVALID_ARGUMENTS
Parameters
_HHessian matrix.
If Hessian matrix is trivial, a NULL pointer can be passed.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations when using initial homotopy.
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP initialisation.
Output: CPU time spend for QP initialisation.
xOptOptimal primal solution vector. A NULL pointer can be passed.
yOptOptimal dual solution vector. A NULL pointer can be passed.
guessedBoundsOptimal working set for solution (xOpt,yOpt). A NULL pointer can be passed.

Definition at line 354 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::init ( const char *const  H_file,
const char *const  g_file,
const char *const  lb_file,
const char *const  ub_file,
int &  nWSR,
real_t *const  cputime,
const real_t *const  xOpt,
const real_t *const  yOpt,
const Bounds *const  guessedBounds 
)

Initialises a QProblemB with given QP data to be read from files and solves it depending on the parameter constellation:

  1. 0, 0, 0 : start with xOpt = 0, yOpt = 0 and IB empty (or all implicit equality bounds),
  2. xOpt, 0, 0 : start with xOpt, yOpt = 0 and obtain IB by "clipping",
  3. 0, yOpt, 0 : start with xOpt = 0, yOpt and obtain IB from yOpt != 0,
  4. 0, 0, IB: start with xOpt = 0, yOpt = 0 and IB,
  5. xOpt, yOpt, 0 : start with xOpt, yOpt and obtain IB from yOpt != 0,
  6. xOpt, 0, IB: start with xOpt, yOpt = 0 and IB,
  7. xOpt, yOpt, IB: start with xOpt, yOpt and IB (assume them to be consistent!) Note: This function internally calls solveInitialQP for initialisation!
    Returns
    SUCCESSFUL_RETURN
    RET_INIT_FAILED
    RET_INIT_FAILED_CHOLESKY
    RET_INIT_FAILED_HOTSTART
    RET_INIT_FAILED_INFEASIBILITY
    RET_INIT_FAILED_UNBOUNDEDNESS
    RET_MAX_NWSR_REACHED
    RET_UNABLE_TO_READ_FILE
Parameters
H_fileName of file where Hessian matrix is stored.
If Hessian matrix is trivial, a NULL pointer can be passed.
g_fileName of file where gradient vector is stored.
lb_fileName of file where lower bound vector.
If no lower bounds exist, a NULL pointer can be passed.
ub_fileName of file where upper bound vector.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations when using initial homotopy.
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP initialisation.
Output: CPU time spend for QP initialisation.
xOptOptimal primal solution vector. A NULL pointer can be passed.
yOptOptimal dual solution vector. A NULL pointer can be passed.
guessedBoundsOptimal working set for solution (xOpt,yOpt). A NULL pointer can be passed.

Definition at line 399 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

BooleanType QProblemB::isBlocking ( real_t  num,
real_t  den,
real_t  epsNum,
real_t  epsDen,
real_t t 
) const
inlineprotected

Checks whether given ratio is blocking, i.e. limits the maximum step length along the homotopy path to a value lower than given one.

Returns
SUCCESSFUL_RETURN
Parameters
numNumerator for performing the ratio test.
denDenominator for performing the ratio test.
epsNumNumerator tolerance.
epsDenDenominator tolerance.
tInput: Current maximum step length along the homotopy path, Output: Updated maximum possible step length along the homotopy path.
BooleanType QProblemB::isBlocking ( real_t  num,
real_t  den,
real_t  epsNum,
real_t  epsDen,
real_t t 
) const
inlineprotected

Checks whether given ratio is blocking, i.e. limits the maximum step length along the homotopy path to a value lower than given one.

Returns
SUCCESSFUL_RETURN
Parameters
numNumerator for performing the ratio test.
denDenominator for performing the ratio test.
epsNumNumerator tolerance.
epsDenDenominator tolerance.
tInput: Current maximum step length along the homotopy path, Output: Updated maximum possible step length along the homotopy path.
BooleanType QProblemB::isCPUtimeLimitExceeded ( const real_t *const  cputime,
real_t  starttime,
int_t  nWSR 
) const
protected

Determines if next QP iteration can be performed within given CPU time limit.

Returns
BT_TRUE: CPU time limit is exceeded, stop QP solution.
BT_FALSE: Sufficient CPU time for next QP iteration.
Parameters
cputimeMaximum CPU time allowed for QP solution.
starttimeStart time of current QP solution.
nWSRNumber of working set recalculations performed so far.
BooleanType QProblemB::isCPUtimeLimitExceeded ( const real_t *const  cputime,
real_t  starttime,
int  nWSR 
) const
protected

Determines if next QP iteration can be performed within given CPU time limit.

Returns
BT_TRUE: CPU time limit is exceeded, stop QP solution.
BT_FALSE: Sufficient CPU time for next QP iteration.
Parameters
cputimeMaximum CPU time allowed for QP solution.
starttimeStart time of current QP solution.
nWSRNumber of working set recalculations performed so far.

Definition at line 2021 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

BooleanType QProblemB::isInfeasible ( ) const
inline

Returns if the QP is infeasible.

Returns
BT_TRUE: QP infeasible
BT_FALSE: QP feasible (or not known to be infeasible!)
BooleanType QProblemB::isInfeasible ( ) const
inline

Returns if the QP is infeasible.

Returns
BT_TRUE: QP infeasible
BT_FALSE: QP feasible (or not known to be infeasible!)
BooleanType QProblemB::isInfeasible ( ) const
inline

Returns if the QP is infeasible.

Returns
BT_TRUE: QP infeasible
BT_FALSE: QP feasible (or not known to be infeasible!)
BooleanType QProblemB::isInfeasible ( ) const
inline

Returns if the QP is infeasible.

Returns
BT_TRUE: QP infeasible
BT_FALSE: QP feasible (or not known to be infeasible!)
BooleanType QProblemB::isInitialised ( ) const
inline

Returns if the QProblem object is initialised.

Returns
BT_TRUE: QProblemB initialised
BT_FALSE: QProblemB not initialised
BooleanType QProblemB::isInitialised ( ) const
inline

Returns if the QProblem object is initialised.

Returns
BT_TRUE: QProblemB initialised
BT_FALSE: QProblemB not initialised
BooleanType QProblemB::isInitialised ( ) const
inline

Returns if the QProblem object is initialised.

Returns
BT_TRUE: QProblemB initialised
BT_FALSE: QProblemB not initialised
BooleanType QProblemB::isInitialised ( ) const
inline

Returns if the QProblem object is initialised.

Returns
BT_TRUE: QProblemB initialised
BT_FALSE: QProblemB not initialised
BooleanType QProblemB::isSolved ( ) const
inline

Returns if the QP has been solved.

Returns
BT_TRUE: QProblemB solved
BT_FALSE: QProblemB not solved
BooleanType QProblemB::isSolved ( ) const
inline

Returns if the QP has been solved.

Returns
BT_TRUE: QProblemB solved
BT_FALSE: QProblemB not solved
BooleanType QProblemB::isSolved ( ) const
inline

Returns if the QP has been solved.

Returns
BT_TRUE: QProblemB solved
BT_FALSE: QProblemB not solved
BooleanType QProblemB::isSolved ( ) const
inline

Returns if the QP has been solved.

Returns
BT_TRUE: QProblemB solved
BT_FALSE: QProblemB not solved
BooleanType QProblemB::isUnbounded ( ) const
inline

Returns if the QP is unbounded.

Returns
BT_TRUE: QP unbounded
BT_FALSE: QP unbounded (or not known to be unbounded!)
BooleanType QProblemB::isUnbounded ( ) const
inline

Returns if the QP is unbounded.

Returns
BT_TRUE: QP unbounded
BT_FALSE: QP unbounded (or not known to be unbounded!)
BooleanType QProblemB::isUnbounded ( ) const
inline

Returns if the QP is unbounded.

Returns
BT_TRUE: QP unbounded
BT_FALSE: QP unbounded (or not known to be unbounded!)
BooleanType QProblemB::isUnbounded ( ) const
inline

Returns if the QP is unbounded.

Returns
BT_TRUE: QP unbounded
BT_FALSE: QP unbounded (or not known to be unbounded!)
returnValue QProblemB::loadQPvectorsFromFile ( const char *const  g_file,
const char *const  lb_file,
const char *const  ub_file,
real_t *const  g_new,
real_t *const  lb_new,
real_t *const  ub_new 
) const
protected

Loads new QP vectors from files (internal members are not affected!).

Returns
SUCCESSFUL_RETURN
RET_UNABLE_TO_OPEN_FILE
RET_UNABLE_TO_READ_FILE
RET_INVALID_ARGUMENTS
Parameters
g_fileName of file where gradient, of neighbouring QP to be solved, is stored.
lb_fileName of file where lower bounds, of neighbouring QP to be solved, is stored.
If no lower bounds exist, a NULL pointer can be passed.
ub_fileName of file where upper bounds, of neighbouring QP to be solved, is stored.
If no upper bounds exist, a NULL pointer can be passed.
g_newOutput: Gradient of neighbouring QP to be solved.
lb_newOutput: Lower bounds of neighbouring QP to be solved
ub_newOutput: Upper bounds of neighbouring QP to be solved
returnValue QProblemB::loadQPvectorsFromFile ( const char *const  g_file,
const char *const  lb_file,
const char *const  ub_file,
real_t *const  g_new,
real_t *const  lb_new,
real_t *const  ub_new 
) const
protected

Loads new QP vectors from files (internal members are not affected!).

Returns
SUCCESSFUL_RETURN
RET_UNABLE_TO_OPEN_FILE
RET_UNABLE_TO_READ_FILE
RET_INVALID_ARGUMENTS
Parameters
g_fileName of file where gradient, of neighbouring QP to be solved, is stored.
lb_fileName of file where lower bounds, of neighbouring QP to be solved, is stored.
If no lower bounds exist, a NULL pointer can be passed.
ub_fileName of file where upper bounds, of neighbouring QP to be solved, is stored.
If no upper bounds exist, a NULL pointer can be passed.
g_newOutput: Gradient of neighbouring QP to be solved.
lb_newOutput: Lower bounds of neighbouring QP to be solved
ub_newOutput: Upper bounds of neighbouring QP to be solved

Definition at line 1945 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::obtainAuxiliaryWorkingSet ( const real_t *const  xOpt,
const real_t *const  yOpt,
const Bounds *const  guessedBounds,
Bounds auxiliaryBounds 
) const
protected

Obtains the desired working set for the auxiliary initial QP in accordance with the user specifications

Returns
SUCCESSFUL_RETURN
RET_OBTAINING_WORKINGSET_FAILED
RET_INVALID_ARGUMENTS
Parameters
xOptOptimal primal solution vector. If a NULL pointer is passed, all entries are assumed to be zero.
yOptOptimal dual solution vector. If a NULL pointer is passed, all entries are assumed to be zero.
guessedBoundsGuessed working set for solution (xOpt,yOpt).
auxiliaryBoundsInput: Allocated bound object.
Ouput: Working set for auxiliary QP.

Definition at line 900 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::obtainAuxiliaryWorkingSet ( const real_t *const  xOpt,
const real_t *const  yOpt,
const Bounds *const  guessedBounds,
Bounds auxiliaryBounds 
) const
protected

Obtains the desired working set for the auxiliary initial QP in accordance with the user specifications

Returns
SUCCESSFUL_RETURN
RET_OBTAINING_WORKINGSET_FAILED
RET_INVALID_ARGUMENTS
Parameters
xOptOptimal primal solution vector. If a NULL pointer is passed, all entries are assumed to be zero.
yOptOptimal dual solution vector. If a NULL pointer is passed, all entries are assumed to be zero.
guessedBoundsGuessed working set for solution (xOpt,yOpt).
auxiliaryBoundsInput: Allocated bound object.
Ouput: Working set for auxiliary QP.
returnValue QProblemB::obtainAuxiliaryWorkingSet ( const real_t *const  xOpt,
const real_t *const  yOpt,
const Bounds *const  guessedBounds,
Bounds auxiliaryBounds 
) const
protected

Obtains the desired working set for the auxiliary initial QP in accordance with the user specifications

Returns
SUCCESSFUL_RETURN
RET_OBTAINING_WORKINGSET_FAILED
RET_INVALID_ARGUMENTS
Parameters
xOptOptimal primal solution vector. If a NULL pointer is passed, all entries are assumed to be zero.
yOptOptimal dual solution vector. If a NULL pointer is passed, all entries are assumed to be zero.
guessedBoundsGuessed working set for solution (xOpt,yOpt).
auxiliaryBoundsInput: Allocated bound object.
Output: Working set for auxiliary QP.
returnValue QProblemB::obtainAuxiliaryWorkingSet ( const real_t *const  xOpt,
const real_t *const  yOpt,
const Bounds *const  guessedBounds,
Bounds auxiliaryBounds 
) const
protected

Obtains the desired working set for the auxiliary initial QP in accordance with the user specifications

Returns
SUCCESSFUL_RETURN
RET_OBTAINING_WORKINGSET_FAILED
RET_INVALID_ARGUMENTS
Parameters
xOptOptimal primal solution vector. If a NULL pointer is passed, all entries are assumed to be zero.
yOptOptimal dual solution vector. If a NULL pointer is passed, all entries are assumed to be zero.
guessedBoundsGuessed working set for solution (xOpt,yOpt).
auxiliaryBoundsInput: Allocated bound object.
Ouput: Working set for auxiliary QP.
QProblemB & QProblemB::operator= ( const QProblemB rhs)

Assignment operator (deep copy).

Parameters
rhsRhs object.

Definition at line 183 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

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

Assignment operator (deep copy).

Parameters
rhsRhs object.
virtual QProblemB& QProblemB::operator= ( const QProblemB rhs)
virtual

Assignment operator (deep copy).

Parameters
rhsRhs object.
QProblemB& QProblemB::operator= ( const QProblemB rhs)

Assignment operator (deep copy).

Parameters
rhsRhs object.
virtual returnValue QProblemB::performDriftCorrection ( )
privatevirtual

Drift correction at end of each active set iteration

Returns
SUCCESSFUL_RETURN

Reimplemented in QProblem, and QProblem.

returnValue QProblemB::performDriftCorrection ( )
private

Drift correction at end of each active set iteration

Returns
SUCCESSFUL_RETURN

Definition at line 3319 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

virtual returnValue QProblemB::performRamping ( )
protectedvirtual

Ramping Strategy to avoid ties. Modifies homotopy start without changing current active set.

Returns
SUCCESSFUL_RETURN

Reimplemented in QProblem, and QProblem.

returnValue QProblemB::performRamping ( )
protectedvirtual

Ramping Strategy to avoid ties. Modifies homotopy start without changing current active set.

Returns
SUCCESSFUL_RETURN

Reimplemented in QProblem, and QProblem.

Definition at line 2168 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::performRatioTest ( int_t  nIdx,
const int_t *const  idxList,
const SubjectTo *const  subjectTo,
const real_t *const  num,
const real_t *const  den,
real_t  epsNum,
real_t  epsDen,
real_t t,
int_t BC_idx 
) const
protected

Performs robustified ratio test yield the maximum possible step length along the homotopy path.

Returns
SUCCESSFUL_RETURN
Parameters
nIdxNumber of ratios to be checked.
idxListArray containing the indices of all ratios to be checked.
subjectToBound/Constraint object corresponding to ratios to be checked.
numArray containing all numerators for performing the ratio test.
denArray containing all denominators for performing the ratio test.
epsNumNumerator tolerance.
epsDenDenominator tolerance.
tOutput: Maximum possible step length along the homotopy path.
BC_idxOutput: Index of blocking constraint.
returnValue QProblemB::performRatioTest ( int  nIdx,
const int *const  idxList,
const SubjectTo *const  subjectTo,
const real_t *const  num,
const real_t *const  den,
real_t  epsNum,
real_t  epsDen,
real_t t,
int &  BC_idx 
) const
protected

Performs robustified ratio test yield the maximum possible step length along the homotopy path.

Returns
SUCCESSFUL_RETURN
Parameters
nIdxNumber of ratios to be checked.
idxListArray containing the indices of all ratios to be checked.
subjectToBound/Constraint object corresponding to ratios to be checked.
numArray containing all numerators for performing the ratio test.
denArray containing all denominators for performing the ratio test.
epsNumNumerator tolerance.
epsDenDenominator tolerance.
tOutput: Maximum possible step length along the homotopy path.
BC_idxOutput: Index of blocking constraint.

Definition at line 2081 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::performStep ( const real_t *const  delta_g,
const real_t *const  delta_lb,
const real_t *const  delta_ub,
const real_t *const  delta_xFX,
const real_t *const  delta_xFR,
const real_t *const  delta_yFX,
int_t BC_idx,
SubjectToStatus BC_status 
)
private

Determines the maximum possible step length along the homotopy path and performs this step (without changing working set).

Returns
SUCCESSFUL_RETURN
RET_QP_INFEASIBLE
Parameters
delta_gStep direction of gradient.
delta_lbStep direction of lower bounds.
delta_ubStep direction of upper bounds.
delta_xFXPrimal homotopy step direction of fixed variables.
delta_xFRPrimal homotopy step direction of free variables.
delta_yFXDual homotopy step direction of fixed variables' multiplier.
BC_idxOutput: Index of blocking constraint.
BC_statusOutput: Status of blocking constraint.
returnValue QProblemB::performStep ( const real_t *const  delta_g,
const real_t *const  delta_lb,
const real_t *const  delta_ub,
const real_t *const  delta_xFX,
const real_t *const  delta_xFR,
const real_t *const  delta_yFX,
int &  BC_idx,
SubjectToStatus BC_status 
)
private

Determines the maximum possible step length along the homotopy path and performs this step (without changing working set).

Returns
SUCCESSFUL_RETURN
RET_QP_INFEASIBLE
Parameters
delta_gStep direction of gradient.
delta_lbStep direction of lower bounds.
delta_ubStep direction of upper bounds.
delta_xFXPrimal homotopy step direction of fixed variables.
delta_xFRPrimal homotopy step direction of free variables.
delta_yFXDual homotopy step direction of fixed variables' multiplier.
BC_idxOutput: Index of blocking constraint.
BC_statusOutput: Status of blocking constraint.

Definition at line 3125 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::printIteration ( int_t  iter,
int_t  BC_idx,
SubjectToStatus  BC_status,
real_t  homotopyLength,
BooleanType  isFirstCall = BT_TRUE 
)
private

Prints concise information on the current iteration.

Returns
SUCCESSFUL_RETURN
Parameters
iterNumber of current iteration.
BC_idxIndex of blocking bound.
BC_statusStatus of blocking bound.
homotopyLengthCurrent homotopy distance.
isFirstCallIndicating whether this is the first call for current QP.

Definition at line 3685 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::printIteration ( int  iteration,
int  BC_idx,
SubjectToStatus  BC_status 
)
private

Prints concise information on the current iteration.

Returns
SUCCESSFUL_RETURN
Parameters
iterationNumber of current iteration.
BC_idxIndex of blocking bound.
BC_statusStatus of blocking bound.

Definition at line 3588 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::printOptions ( ) const

Prints a list of all options and their current values.

Returns
SUCCESSFUL_RETURN
returnValue QProblemB::printOptions ( ) const

Prints a list of all options and their current values.

Returns
SUCCESSFUL_RETURN

Definition at line 1138 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

virtual returnValue QProblemB::printProperties ( )
virtual

Prints concise list of properties of the current QP.

Returns
SUCCESSFUL_RETURN

Reimplemented in QProblem, and QProblem.

returnValue QProblemB::printProperties ( )
virtual

Prints concise list of properties of the current QP.

Returns
SUCCESSFUL_RETURN

Reimplemented in QProblem, and QProblem.

Definition at line 1013 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::regulariseHessian ( )
protected

Regularise Hessian matrix by adding a scaled identity matrix to it.

Returns
SUCCESSFUL_RETURN
RET_HESSIAN_ALREADY_REGULARISED
returnValue QProblemB::regulariseHessian ( )
protected

Regularise Hessian matrix by adding a scaled identity matrix to it.

Returns
SUCCESSFUL_RETURN
RET_HESSIAN_ALREADY_REGULARISED

Definition at line 2049 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

real_t QProblemB::relativeHomotopyLength ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new 
)
protected

Compute relative length of homotopy in data space for termination criterion.

Returns
Relative length in data space.
Parameters
g_newFinal gradient.
lb_newFinal lower variable bounds.
ub_newFinal upper variable bounds.

Definition at line 2129 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::removeBound ( int  number,
BooleanType  updateCholesky 
)
protected

Removes a bounds from active set (specialised version for the case where no constraints exist).

Returns
SUCCESSFUL_RETURN
RET_HESSIAN_NOT_SPD
RET_REMOVEBOUND_FAILED
Parameters
numberNumber of bound to be removed from active set.
updateCholeskyFlag indicating if Cholesky decomposition shall be updated.

Definition at line 1287 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::removeBound ( int  number,
BooleanType  updateCholesky 
)
protected

Removes a bounds from active set (specialised version for the case where no constraints exist).

Returns
SUCCESSFUL_RETURN
RET_HESSIAN_NOT_SPD
RET_REMOVEBOUND_FAILED
Parameters
numberNumber of bound to be removed from active set.
updateCholeskyFlag indicating if Cholesky decomposition shall be updated.
returnValue QProblemB::removeBound ( int_t  number,
BooleanType  updateCholesky 
)
private

Removes a bounds from active set (specialised version for the case where no constraints exist).

Returns
SUCCESSFUL_RETURN
RET_HESSIAN_NOT_SPD
RET_REMOVEBOUND_FAILED
Parameters
numberNumber of bound to be removed from active set.
updateCholeskyFlag indicating if Cholesky decomposition shall be updated.
returnValue QProblemB::removeBound ( int  number,
BooleanType  updateCholesky 
)
private

Removes a bounds from active set (specialised version for the case where no constraints exist).

Returns
SUCCESSFUL_RETURN
RET_HESSIAN_NOT_SPD
RET_REMOVEBOUND_FAILED
Parameters
numberNumber of bound to be removed from active set.
updateCholeskyFlag indicating if Cholesky decomposition shall be updated.
returnValue QProblemB::reset ( )

Clears all data structures of QProblemB except for QP data.

Returns
SUCCESSFUL_RETURN
RET_RESET_FAILED

0) Reset has Hessian flag.

Definition at line 238 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::reset ( )

Clears all data structures of QProblemB except for QP data.

Returns
SUCCESSFUL_RETURN
RET_RESET_FAILED
virtual returnValue QProblemB::reset ( )
virtual

Clears all data structures of QProblemB except for QP data.

Returns
SUCCESSFUL_RETURN
RET_RESET_FAILED

Reimplemented in SQProblemSchur, QProblem, QProblem, QProblem, and QProblem.

virtual returnValue QProblemB::reset ( )
virtual

Clears all data structures of QProblemB except for QP data.

Returns
SUCCESSFUL_RETURN
RET_RESET_FAILED

Reimplemented in SQProblemSchur, QProblem, QProblem, QProblem, and QProblem.

returnValue QProblemB::resetCounter ( )
inline

Resets QP problem counter (to zero).

Returns
SUCCESSFUL_RETURN.
returnValue QProblemB::setG ( const real_t *const  g_new)
inlineprotected

Changes gradient vector of the QP.

Returns
SUCCESSFUL_RETURN
Parameters
g_newNew gradient vector (with correct dimension!).
returnValue QProblemB::setG ( const real_t *const  g_new)
inlineprotected

Changes gradient vector of the QP.

Returns
SUCCESSFUL_RETURN
Parameters
g_newNew gradient vector (with correct dimension!).
returnValue QProblemB::setG ( const real_t *const  g_new)
inlineprotected

Changes gradient vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
Parameters
g_newNew gradient vector (with correct dimension!).
returnValue QProblemB::setG ( const real_t *const  g_new)
inlineprotected

Changes gradient vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
Parameters
g_newNew gradient vector (with correct dimension!).
returnValue QProblemB::setH ( const real_t *const  H_new)
inlineprotected

Sets Hessian matrix of the QP.

Returns
SUCCESSFUL_RETURN
Parameters
H_newNew Hessian matrix (with correct dimension!).
returnValue QProblemB::setH ( const real_t *const  H_new)
inlineprotected

Sets Hessian matrix of the QP.

Returns
SUCCESSFUL_RETURN
Parameters
H_newNew Hessian matrix (with correct dimension!).
returnValue QProblemB::setH ( SymmetricMatrix H_new)
inlineprotected

Sets Hessian matrix of the QP.

Returns
SUCCESSFUL_RETURN
Parameters
H_newNew Hessian matrix (a shallow copy is made).
returnValue QProblemB::setH ( const real_t *const  H_new)
inlineprotected

Sets dense Hessian matrix of the QP. If a null pointer is passed and a) hessianType is HST_IDENTITY, nothing is done, b) hessianType is not HST_IDENTITY, Hessian matrix is set to zero.

Returns
SUCCESSFUL_RETURN
Parameters
H_newNew dense Hessian matrix (with correct dimension!), a shallow copy is made.
returnValue QProblemB::setH ( SymmetricMatrix H_new)
inlineprotected

Sets Hessian matrix of the QP.

Returns
SUCCESSFUL_RETURN
Parameters
H_newNew Hessian matrix.
returnValue QProblemB::setH ( const real_t *const  H_new)
inlineprotected

Sets dense Hessian matrix of the QP. If a null pointer is passed and a) hessianType is HST_IDENTITY, nothing is done, b) hessianType is not HST_IDENTITY, Hessian matrix is set to zero.

Returns
SUCCESSFUL_RETURN
Parameters
H_newNew dense Hessian matrix (with correct dimension!).
returnValue QProblemB::setHessianType ( HessianType  _hessianType)
inline

Changes the print level.

Returns
SUCCESSFUL_RETURN
Parameters
_hessianTypeNew Hessian type.
returnValue QProblemB::setHessianType ( HessianType  _hessianType)
inline

Changes the print level.

Returns
SUCCESSFUL_RETURN
Parameters
_hessianTypeNew Hessian type.
returnValue QProblemB::setHessianType ( HessianType  _hessianType)
inline

Changes the print level.

Returns
SUCCESSFUL_RETURN
Parameters
_hessianTypeNew Hessian type.
returnValue QProblemB::setHessianType ( HessianType  _hessianType)
inline

Changes the print level.

Returns
SUCCESSFUL_RETURN
Parameters
_hessianTypeNew Hessian type.
returnValue QProblemB::setInfeasibilityFlag ( returnValue  returnvalue,
BooleanType  doThrowError = BT_FALSE 
)
protected

Sets internal infeasibility flag and throws given error in case the far bound strategy is not enabled (as QP might actually not be infeasible in this case).

Returns
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_ENSURELI_FAILED_CYCLING
RET_ENSURELI_FAILED_NOINDEX
Parameters
returnvalueReturnvalue to be tunneled.
doThrowErrorFlag forcing to throw an error.

Definition at line 1932 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::setInfeasibilityFlag ( returnValue  returnvalue)
protected

Sets internal infeasibility flag and throws given error in case the far bound strategy is not enabled (as QP might actually not be infeasible in this case).

Returns
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_ENSURELI_FAILED_CYCLING
RET_ENSURELI_FAILED_NOINDEX

Definition at line 2006 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::setLB ( const real_t *const  lb_new)
inlineprotected

Changes lower bound vector of the QP.

Returns
SUCCESSFUL_RETURN
Parameters
lb_newNew lower bound vector (with correct dimension!).
returnValue QProblemB::setLB ( int  number,
real_t  value 
)
inlineprotected

Changes single entry of lower bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INDEX_OUT_OF_BOUNDS
Parameters
numberNumber of entry to be changed.
valueNew value for entry of lower bound vector.
returnValue QProblemB::setLB ( const real_t *const  lb_new)
inlineprotected

Changes lower bound vector of the QP.

Returns
SUCCESSFUL_RETURN
Parameters
lb_newNew lower bound vector (with correct dimension!).
returnValue QProblemB::setLB ( int  number,
real_t  value 
)
inlineprotected

Changes single entry of lower bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INDEX_OUT_OF_BOUNDS
Parameters
numberNumber of entry to be changed.
valueNew value for entry of lower bound vector.
returnValue QProblemB::setLB ( const real_t *const  lb_new)
inlineprotected

Changes lower bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_QPOBJECT_NOT_SETUP
Parameters
lb_newNew lower bound vector (with correct dimension!).
returnValue QProblemB::setLB ( int_t  number,
real_t  value 
)
inlineprotected

Changes single entry of lower bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_QPOBJECT_NOT_SETUP
RET_INDEX_OUT_OF_BOUNDS
Parameters
numberNumber of entry to be changed.
valueNew value for entry of lower bound vector.
returnValue QProblemB::setLB ( const real_t *const  lb_new)
inlineprotected

Changes lower bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
Parameters
lb_newNew lower bound vector (with correct dimension!).
returnValue QProblemB::setLB ( int  number,
real_t  value 
)
inlineprotected

Changes single entry of lower bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INDEX_OUT_OF_BOUNDS
Parameters
numberNumber of entry to be changed.
valueNew value for entry of lower bound vector.
returnValue QProblemB::setOptions ( const Options _options)
inline

Overrides current options with given ones.

Returns
SUCCESSFUL_RETURN
Parameters
_optionsNew options.
returnValue QProblemB::setOptions ( const Options _options)
inline

Overrides current options with given ones.

Returns
SUCCESSFUL_RETURN
Parameters
_optionsNew options.
returnValue QProblemB::setPrintLevel ( PrintLevel  _printlevel)

Changes the print level.

Returns
SUCCESSFUL_RETURN
Parameters
_printlevelNew print level.

Definition at line 588 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::setPrintLevel ( PrintLevel  _printlevel)

Changes the print level.

Returns
SUCCESSFUL_RETURN
Parameters
_printlevelNew print level.
returnValue QProblemB::setPrintLevel ( PrintLevel  _printlevel)

Changes the print level.

Returns
SUCCESSFUL_RETURN
Parameters
_printlevelNew print level.
returnValue QProblemB::setPrintLevel ( PrintLevel  _printlevel)

Changes the print level.

Returns
SUCCESSFUL_RETURN
Parameters
_printlevelNew print level.
returnValue QProblemB::setUB ( const real_t *const  ub_new)
inlineprotected

Changes upper bound vector of the QP.

Returns
SUCCESSFUL_RETURN
Parameters
ub_newNew upper bound vector (with correct dimension!).
returnValue QProblemB::setUB ( int  number,
real_t  value 
)
inlineprotected

Changes single entry of upper bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INDEX_OUT_OF_BOUNDS
Parameters
numberNumber of entry to be changed.
valueNew value for entry of upper bound vector.
returnValue QProblemB::setUB ( const real_t *const  ub_new)
inlineprotected

Changes upper bound vector of the QP.

Returns
SUCCESSFUL_RETURN
Parameters
ub_newNew upper bound vector (with correct dimension!).
returnValue QProblemB::setUB ( int  number,
real_t  value 
)
inlineprotected

Changes single entry of upper bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INDEX_OUT_OF_BOUNDS
Parameters
numberNumber of entry to be changed.
valueNew value for entry of upper bound vector.
returnValue QProblemB::setUB ( const real_t *const  ub_new)
inlineprotected

Changes upper bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_QPOBJECT_NOT_SETUP
Parameters
ub_newNew upper bound vector (with correct dimension!).
returnValue QProblemB::setUB ( int_t  number,
real_t  value 
)
inlineprotected

Changes single entry of upper bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_QPOBJECT_NOT_SETUP
RET_INDEX_OUT_OF_BOUNDS
Parameters
numberNumber of entry to be changed.
valueNew value for entry of upper bound vector.
returnValue QProblemB::setUB ( const real_t *const  ub_new)
inlineprotected

Changes upper bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
Parameters
ub_newNew upper bound vector (with correct dimension!).
returnValue QProblemB::setUB ( int  number,
real_t  value 
)
inlineprotected

Changes single entry of upper bound vector of the QP.

Returns
SUCCESSFUL_RETURN
RET_INDEX_OUT_OF_BOUNDS
Parameters
numberNumber of entry to be changed.
valueNew value for entry of upper bound vector.
virtual returnValue QProblemB::setupAuxiliaryQP ( const Bounds *const  guessedBounds)
protectedvirtual

Updates QP vectors, working sets and internal data structures in order to start from an optimal solution corresponding to initial guesses of the working set for bounds

Returns
SUCCESSFUL_RETURN
RET_SETUP_AUXILIARYQP_FAILED
Parameters
guessedBoundsInitial guess for working set of bounds.
returnValue QProblemB::setupAuxiliaryQP ( const Bounds *const  guessedBounds)
private

Updates QP vectors, working sets and internal data structures in order to start from an optimal solution corresponding to initial guesses of the working set for bounds

Returns
SUCCESSFUL_RETURN
RET_SETUP_AUXILIARYQP_FAILED
Parameters
guessedBoundsInitial guess for working set of bounds.

Definition at line 2896 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::setupAuxiliaryQPbounds ( BooleanType  useRelaxation)
protected

Setups bounds of the auxiliary initial QP for given optimal primal/dual solution and given initial working set (assumes that members X, Y and BOUNDS have already been initialised!).

Returns
SUCCESSFUL_RETURN
RET_UNKNOWN BUG
Parameters
useRelaxationFlag indicating if inactive bounds shall be relaxed.

Definition at line 1161 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::setupAuxiliaryQPbounds ( BooleanType  useRelaxation)
protected

Setups bounds of the auxiliary initial QP for given optimal primal/dual solution and given initial working set (assumes that members X, Y and BOUNDS have already been initialised!).

Returns
SUCCESSFUL_RETURN
RET_UNKNOWN BUG
Parameters
useRelaxationFlag indicating if inactive bounds shall be relaxed.
returnValue QProblemB::setupAuxiliaryQPbounds ( BooleanType  useRelaxation)
private

Sets up bounds of the auxiliary initial QP for given optimal primal/dual solution and given initial working set (assumes that members X, Y and BOUNDS have already been initialised!).

Returns
SUCCESSFUL_RETURN
RET_UNKNOWN_BUG
Parameters
useRelaxationFlag indicating if inactive bounds shall be relaxed.
returnValue QProblemB::setupAuxiliaryQPbounds ( BooleanType  useRelaxation)
private

Setups bounds of the auxiliary initial QP for given optimal primal/dual solution and given initial working set (assumes that members X, Y and BOUNDS have already been initialised!).

Returns
SUCCESSFUL_RETURN
RET_UNKNOWN_BUG
Parameters
useRelaxationFlag indicating if inactive bounds shall be relaxed.
returnValue QProblemB::setupAuxiliaryQPgradient ( )
protected

Setups gradient of the auxiliary initial QP for given optimal primal/dual solution and given initial working set (assumes that members X, Y and BOUNDS have already been initialised!).

Returns
SUCCESSFUL_RETURN

Definition at line 1137 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::setupAuxiliaryQPgradient ( )
protected

Setups gradient of the auxiliary initial QP for given optimal primal/dual solution and given initial working set (assumes that members X, Y and BOUNDS have already been initialised!).

Returns
SUCCESSFUL_RETURN
returnValue QProblemB::setupAuxiliaryQPgradient ( )
private

Sets up gradient of the auxiliary initial QP for given optimal primal/dual solution and given initial working set (assumes that members X, Y and BOUNDS have already been initialised!).

Returns
SUCCESSFUL_RETURN
returnValue QProblemB::setupAuxiliaryQPgradient ( )
private

Setups gradient of the auxiliary initial QP for given optimal primal/dual solution and given initial working set (assumes that members X, Y and BOUNDS have already been initialised!).

Returns
SUCCESSFUL_RETURN
returnValue QProblemB::setupAuxiliaryQPsolution ( const real_t *const  xOpt,
const real_t *const  yOpt 
)
protected

Setups the optimal primal/dual solution of the auxiliary initial QP.

Returns
SUCCESSFUL_RETURN
Parameters
xOptOptimal primal solution vector. If a NULL pointer is passed, all entries are set to zero.
yOptOptimal dual solution vector. If a NULL pointer is passed, all entries are set to zero.

Definition at line 1096 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::setupAuxiliaryQPsolution ( const real_t *const  xOpt,
const real_t *const  yOpt 
)
protected

Setups the optimal primal/dual solution of the auxiliary initial QP.

Returns
SUCCESSFUL_RETURN
Parameters
xOptOptimal primal solution vector. If a NULL pointer is passed, all entries are set to zero.
yOptOptimal dual solution vector. If a NULL pointer is passed, all entries are set to zero.
returnValue QProblemB::setupAuxiliaryQPsolution ( const real_t *const  xOpt,
const real_t *const  yOpt 
)
private

Sets up the optimal primal/dual solution of the auxiliary initial QP.

Returns
SUCCESSFUL_RETURN
Parameters
xOptOptimal primal solution vector. If a NULL pointer is passed, all entries are set to zero.
yOptOptimal dual solution vector. If a NULL pointer is passed, all entries are set to zero.
returnValue QProblemB::setupAuxiliaryQPsolution ( const real_t *const  xOpt,
const real_t *const  yOpt 
)
private

Setups the optimal primal/dual solution of the auxiliary initial QP.

Returns
SUCCESSFUL_RETURN
Parameters
xOptOptimal primal solution vector. If a NULL pointer is passed, all entries are set to zero.
yOptOptimal dual solution vector. If a NULL pointer is passed, all entries are set to zero.
returnValue QProblemB::setupAuxiliaryWorkingSet ( const Bounds *const  auxiliaryBounds,
BooleanType  setupAfresh 
)
protected

Setups bound data structure according to auxiliaryBounds. (If the working set shall be setup afresh, make sure that bounds data structure has been resetted!)

Returns
SUCCESSFUL_RETURN
RET_SETUP_WORKINGSET_FAILED
RET_INVALID_ARGUMENTS
RET_UNKNOWN BUG
Parameters
auxiliaryBoundsWorking set for auxiliary QP.
setupAfreshFlag indicating if given working set shall be setup afresh or by updating the current one.

Definition at line 1029 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::setupAuxiliaryWorkingSet ( const Bounds *const  auxiliaryBounds,
BooleanType  setupAfresh 
)
protected

Setups bound data structure according to auxiliaryBounds. (If the working set shall be setup afresh, make sure that bounds data structure has been resetted!)

Returns
SUCCESSFUL_RETURN
RET_SETUP_WORKINGSET_FAILED
RET_INVALID_ARGUMENTS
RET_UNKNOWN BUG
Parameters
auxiliaryBoundsWorking set for auxiliary QP.
setupAfreshFlag indicating if given working set shall be setup afresh or by updating the current one.
returnValue QProblemB::setupAuxiliaryWorkingSet ( const Bounds *const  auxiliaryBounds,
BooleanType  setupAfresh 
)
private

Sets up bound data structure according to auxiliaryBounds. (If the working set shall be setup afresh, make sure that bounds data structure has been resetted!)

Returns
SUCCESSFUL_RETURN
RET_SETUP_WORKINGSET_FAILED
RET_INVALID_ARGUMENTS
RET_UNKNOWN_BUG
Parameters
auxiliaryBoundsWorking set for auxiliary QP.
setupAfreshFlag indicating if given working set shall be setup afresh or by updating the current one.
returnValue QProblemB::setupAuxiliaryWorkingSet ( const Bounds *const  auxiliaryBounds,
BooleanType  setupAfresh 
)
private

Setups bound data structure according to auxiliaryBounds. (If the working set shall be setup afresh, make sure that bounds data structure has been resetted!)

Returns
SUCCESSFUL_RETURN
RET_SETUP_WORKINGSET_FAILED
RET_INVALID_ARGUMENTS
RET_UNKNOWN_BUG
Parameters
auxiliaryBoundsWorking set for auxiliary QP.
setupAfreshFlag indicating if given working set shall be setup afresh or by updating the current one.
returnValue QProblemB::setupCholeskyDecomposition ( )
protected

Computes the Cholesky decomposition R of the (simply projected) Hessian (i.e. R^T*R = Z^T*H*Z). It only works in the case where Z is a simple projection matrix!

Returns
SUCCESSFUL_RETURN
RET_INDEXLIST_CORRUPTED

Definition at line 723 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::setupCholeskyDecomposition ( )
protected

Computes the Cholesky decomposition R of the (simply projected) Hessian (i.e. R^T*R = Z^T*H*Z). It only works in the case where Z is a simple projection matrix!

Returns
SUCCESSFUL_RETURN
RET_INDEXLIST_CORRUPTED
returnValue QProblemB::setupCholeskyDecomposition ( )
protected

Computes the Cholesky decomposition of the (simply projected) Hessian (i.e. R^T*R = Z^T*H*Z). It only works in the case where Z is a simple projection matrix! Note: If Hessian turns out not to be positive definite, the Hessian type is set to HST_SEMIDEF accordingly.

Returns
SUCCESSFUL_RETURN
RET_HESSIAN_NOT_SPD
RET_INDEXLIST_CORRUPTED
returnValue QProblemB::setupInitialCholesky ( )
protectedvirtual

Computes initial Cholesky decomposition of the (simply projected) Hessian making use of the function computeCholesky().

Returns
SUCCESSFUL_RETURN
RET_HESSIAN_NOT_SPD
RET_INDEXLIST_CORRUPTED

Reimplemented in QProblem.

Definition at line 1441 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::setupQPdata ( const real_t *const  _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub 
)
protected

Setups internal QP data.

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
Parameters
_HHessian matrix.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.

Definition at line 1505 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::setupQPdata ( const real_t *const  _H,
const real_t *const  _R,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub 
)
protected

Setups internal QP data.

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
Parameters
_HHessian matrix.
_RCholesky factorization of the Hessian matrix.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.

Definition at line 1548 of file external_packages/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::setupQPdata ( SymmetricMatrix _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub 
)
protected

Sets up internal QP data.

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
Parameters
_HHessian matrix.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.
returnValue QProblemB::setupQPdata ( const real_t *const  _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub 
)
protected

Sets up internal QP data. If the current Hessian is trivial (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, memory for Hessian is allocated and it is set to the given one.

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
RET_NO_HESSIAN_SPECIFIED
Parameters
_HHessian matrix.
If Hessian matrix is trivial,a NULL pointer can be passed.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.
returnValue QProblemB::setupQPdata ( SymmetricMatrix _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub 
)
protected

Setups internal QP data.

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
Parameters
_HHessian matrix.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.

Definition at line 1787 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::setupQPdata ( const real_t *const  _H,
const real_t *const  _g,
const real_t *const  _lb,
const real_t *const  _ub 
)
protected

Setups internal QP data. If the current Hessian is trivial (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, memory for Hessian is allocated and it is set to the given one.

Returns
SUCCESSFUL_RETURN
RET_INVALID_ARGUMENTS
RET_NO_HESSIAN_SPECIFIED
Parameters
_HHessian matrix.
If Hessian matrix is trivial,a NULL pointer can be passed.
_gGradient vector.
_lbLower bounds (on variables).
If no lower bounds exist, a NULL pointer can be passed.
_ubUpper bounds (on variables).
If no upper bounds exist, a NULL pointer can be passed.
returnValue QProblemB::setupQPdataFromFile ( const char *const  H_file,
const char *const  g_file,
const char *const  lb_file,
const char *const  ub_file 
)
protected

Sets up internal QP data by loading it from files. If the current Hessian is trivial (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, memory for Hessian is allocated and it is set to the given one.

Returns
SUCCESSFUL_RETURN
RET_UNABLE_TO_OPEN_FILE
RET_UNABLE_TO_READ_FILE
RET_INVALID_ARGUMENTS
RET_NO_HESSIAN_SPECIFIED
Parameters
H_fileName of file where Hessian matrix, of neighbouring QP to be solved, is stored.
If Hessian matrix is trivial,a NULL pointer can be passed.
g_fileName of file where gradient, of neighbouring QP to be solved, is stored.
lb_fileName of file where lower bounds, of neighbouring QP to be solved, is stored.
If no lower bounds exist, a NULL pointer can be passed.
ub_fileName of file where upper bounds, of neighbouring QP to be solved, is stored.
If no upper bounds exist, a NULL pointer can be passed.
returnValue QProblemB::setupQPdataFromFile ( const char *const  H_file,
const char *const  g_file,
const char *const  lb_file,
const char *const  ub_file 
)
protected

Setups internal QP data by loading it from files. If the current Hessian is trivial (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, memory for Hessian is allocated and it is set to the given one.

Returns
SUCCESSFUL_RETURN
RET_UNABLE_TO_OPEN_FILE
RET_UNABLE_TO_READ_FILE
RET_INVALID_ARGUMENTS
RET_NO_HESSIAN_SPECIFIED
Parameters
H_fileName of file where Hessian matrix, of neighbouring QP to be solved, is stored.
If Hessian matrix is trivial,a NULL pointer can be passed.
g_fileName of file where gradient, of neighbouring QP to be solved, is stored.
lb_fileName of file where lower bounds, of neighbouring QP to be solved, is stored.
If no lower bounds exist, a NULL pointer can be passed.
ub_fileName of file where upper bounds, of neighbouring QP to be solved, is stored.
If no upper bounds exist, a NULL pointer can be passed.

Definition at line 1873 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::setupSubjectToType ( )
protected

Determines type of constraints and bounds (i.e. implicitly fixed, unbounded etc.).

Returns
SUCCESSFUL_RETURN
RET_SETUPSUBJECTTOTYPE_FAILED

Definition at line 664 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::setupSubjectToType ( )
protected

Determines type of constraints and bounds (i.e. implicitly fixed, unbounded etc.).

Returns
SUCCESSFUL_RETURN
RET_SETUPSUBJECTTOTYPE_FAILED
virtual returnValue QProblemB::setupSubjectToType ( )
protectedvirtual

Determines type of existing constraints and bounds (i.e. implicitly fixed, unbounded etc.).

Returns
SUCCESSFUL_RETURN
RET_SETUPSUBJECTTOTYPE_FAILED

Reimplemented in QProblem, QProblem, QProblem, and QProblem.

virtual returnValue QProblemB::setupSubjectToType ( const real_t *const  lb_new,
const real_t *const  ub_new 
)
protectedvirtual

Determines type of new constraints and bounds (i.e. implicitly fixed, unbounded etc.).

Returns
SUCCESSFUL_RETURN
RET_SETUPSUBJECTTOTYPE_FAILED
Parameters
lb_newNew lower bounds.
ub_newNew upper bounds.
virtual returnValue QProblemB::setupSubjectToType ( )
protectedvirtual

Determines type of existing constraints and bounds (i.e. implicitly fixed, unbounded etc.).

Returns
SUCCESSFUL_RETURN
RET_SETUPSUBJECTTOTYPE_FAILED

Reimplemented in QProblem, QProblem, QProblem, and QProblem.

returnValue QProblemB::setupSubjectToType ( const real_t *const  lb_new,
const real_t *const  ub_new 
)
protectedvirtual

Determines type of new constraints and bounds (i.e. implicitly fixed, unbounded etc.).

Returns
SUCCESSFUL_RETURN
RET_SETUPSUBJECTTOTYPE_FAILED
Parameters
lb_newNew lower bounds.
ub_newNew upper bounds.

Definition at line 1365 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

BooleanType QProblemB::shallRefactorise ( const Bounds *const  guessedBounds) const
private

Determines if it is more efficient to refactorise the matrices when hotstarting or not (i.e. better to update the existing factorisations).

Returns
BT_TRUE iff matrices shall be refactorised afresh
Parameters
guessedBoundsGuessed new working set.
BooleanType QProblemB::shallRefactorise ( const Bounds *const  guessedBounds) const
private

Determines if it is more efficient to refactorise the matrices when hotstarting or not (i.e. better to update the existing factorisations).

Returns
BT_TRUE iff matrices shall be refactorised afresh
Parameters
guessedBoundsGuessed new working set.

Definition at line 3369 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::solveInitialQP ( const real_t *const  xOpt,
const real_t *const  yOpt,
const Bounds *const  guessedBounds,
int &  nWSR,
real_t *const  cputime 
)
protected

Solves a QProblemB whose QP data is assumed to be stored in the member variables. A guess for its primal/dual optimal solution vectors and the corresponding optimal working set can be provided.

Returns
SUCCESSFUL_RETURN
RET_INIT_FAILED
RET_INIT_FAILED_CHOLESKY
RET_INIT_FAILED_HOTSTART
RET_INIT_FAILED_INFEASIBILITY
RET_INIT_FAILED_UNBOUNDEDNESS
RET_MAX_NWSR_REACHED
Parameters
xOptOptimal primal solution vector. A NULL pointer can be passed.
yOptOptimal dual solution vector. A NULL pointer can be passed.
guessedBoundsGuessed working set for solution (xOpt,yOpt). A NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeOutput: CPU time required to solve QP (or to perform nWSR iterations).

Definition at line 791 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/SRC/QProblemB.cpp.

returnValue QProblemB::solveInitialQP ( const real_t *const  xOpt,
const real_t *const  yOpt,
const Bounds *const  guessedBounds,
int &  nWSR,
real_t *const  cputime 
)
protected

Solves a QProblemB whose QP data is assumed to be stored in the member variables. A guess for its primal/dual optimal solution vectors and the corresponding optimal working set can be provided.

Returns
SUCCESSFUL_RETURN
RET_INIT_FAILED
RET_INIT_FAILED_CHOLESKY
RET_INIT_FAILED_HOTSTART
RET_INIT_FAILED_INFEASIBILITY
RET_INIT_FAILED_UNBOUNDEDNESS
RET_MAX_NWSR_REACHED
Parameters
xOptOptimal primal solution vector. A NULL pointer can be passed.
yOptOptimal dual solution vector. A NULL pointer can be passed.
guessedBoundsGuessed working set for solution (xOpt,yOpt). A NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeOutput: CPU time required to solve QP (or to perform nWSR iterations).
returnValue QProblemB::solveInitialQP ( const real_t *const  xOpt,
const real_t *const  yOpt,
const Bounds *const  guessedBounds,
const real_t *const  _R,
int_t nWSR,
real_t *const  cputime 
)
private

Solves a QProblemB whose QP data is assumed to be stored in the member variables. A guess for its primal/dual optimal solution vectors and the corresponding optimal working set can be provided. Note: This function is internally called by all init functions!

Returns
SUCCESSFUL_RETURN
RET_INIT_FAILED
RET_INIT_FAILED_CHOLESKY
RET_INIT_FAILED_HOTSTART
RET_INIT_FAILED_INFEASIBILITY
RET_INIT_FAILED_UNBOUNDEDNESS
RET_MAX_NWSR_REACHED
Parameters
xOptOptimal primal solution vector.
yOptOptimal dual solution vector.
guessedBoundsOptimal working set of bounds for solution (xOpt,yOpt).
_RPre-computed (upper triangular) Cholesky factor of Hessian matrix.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP solution.
Output: CPU time spent for QP solution (or to perform nWSR iterations).

Definition at line 2253 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::solveInitialQP ( const real_t *const  xOpt,
const real_t *const  yOpt,
const Bounds *const  guessedBounds,
int &  nWSR,
real_t *const  cputime 
)
private

Solves a QProblemB whose QP data is assumed to be stored in the member variables. A guess for its primal/dual optimal solution vectors and the corresponding optimal working set can be provided. Note: This function is internally called by all init functions!

Returns
SUCCESSFUL_RETURN
RET_INIT_FAILED
RET_INIT_FAILED_CHOLESKY
RET_INIT_FAILED_HOTSTART
RET_INIT_FAILED_INFEASIBILITY
RET_INIT_FAILED_UNBOUNDEDNESS
RET_MAX_NWSR_REACHED
Parameters
xOptOptimal primal solution vector. A NULL pointer can be passed.
yOptOptimal dual solution vector. A NULL pointer can be passed.
guessedBoundsGuessed working set for solution (xOpt,yOpt). A NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP solution.
Output: CPU time spend for QP solution (or to perform nWSR iterations).
returnValue QProblemB::solveQP ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
int_t nWSR,
real_t *const  cputime,
int_t  nWSRperformed = 0,
BooleanType  isFirstCall = BT_TRUE 
)
private

Solves an initialised QProblemB using online active set strategy. Note: This function is internally called by all hotstart functions!

Returns
SUCCESSFUL_RETURN
RET_MAX_NWSR_REACHED
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED
RET_HOTSTART_FAILED
RET_SHIFT_DETERMINATION_FAILED
RET_STEPDIRECTION_DETERMINATION_FAILED
RET_STEPLENGTH_DETERMINATION_FAILED
RET_HOMOTOPY_STEP_FAILED
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_HOTSTART_STOPPED_UNBOUNDEDNESS
Parameters
g_newGradient of neighbouring QP to be solved.
lb_newLower bounds of neighbouring QP to be solved.
If no lower bounds exist, a NULL pointer can be passed.
ub_newUpper bounds of neighbouring QP to be solved.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP solution.
Output: CPU time spent for QP solution (or to perform nWSR iterations).
nWSRperformedNumber of working set recalculations already performed to solve this QP within previous solveQP() calls. This number is always zero, except for successive calls from solveRegularisedQP() or when using the far bound strategy.
isFirstCallIndicating whether this is the first call for current QP.

Definition at line 2401 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::solveQP ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
int &  nWSR,
real_t *const  cputime,
int  nWSRperformed = 0 
)
private

Solves an initialised QProblemB using online active set strategy. Note: This function is internally called by all hotstart functions!

Returns
SUCCESSFUL_RETURN
RET_MAX_NWSR_REACHED
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED
RET_HOTSTART_FAILED
RET_SHIFT_DETERMINATION_FAILED
RET_STEPDIRECTION_DETERMINATION_FAILED
RET_STEPLENGTH_DETERMINATION_FAILED
RET_HOMOTOPY_STEP_FAILED
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_HOTSTART_STOPPED_UNBOUNDEDNESS
Parameters
g_newGradient of neighbouring QP to be solved.
lb_newLower bounds of neighbouring QP to be solved.
If no lower bounds exist, a NULL pointer can be passed.
ub_newUpper bounds of neighbouring QP to be solved.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP solution.
Output: CPU time spend for QP solution (or to perform nWSR iterations).
nWSRperformedNumber of working set recalculations already performed to solve this QP within previous solveQP() calls. This number is always zero, except for successive calls from solveRegularisedQP() or when using the far bound strategy.

Definition at line 2352 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::solveRegularisedQP ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
int_t nWSR,
real_t *const  cputime,
int_t  nWSRperformed = 0,
BooleanType  isFirstCall = BT_TRUE 
)
private

Solves an initialised QProblemB using online active set strategy. Note: This function is internally called by all hotstart functions!

Returns
SUCCESSFUL_RETURN
RET_MAX_NWSR_REACHED
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED
RET_HOTSTART_FAILED
RET_SHIFT_DETERMINATION_FAILED
RET_STEPDIRECTION_DETERMINATION_FAILED
RET_STEPLENGTH_DETERMINATION_FAILED
RET_HOMOTOPY_STEP_FAILED
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_HOTSTART_STOPPED_UNBOUNDEDNESS
Parameters
g_newGradient of neighbouring QP to be solved.
lb_newLower bounds of neighbouring QP to be solved.
If no lower bounds exist, a NULL pointer can be passed.
ub_newUpper bounds of neighbouring QP to be solved.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP solution.
Output: CPU time spent for QP solution (or to perform nWSR iterations).
nWSRperformedNumber of working set recalculations already performed to solve this QP within previous solveRegularisedQP() calls. This number is always zero, except for successive calls when using the far bound strategy.
isFirstCallIndicating whether this is the first call for current QP.

Definition at line 2648 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

returnValue QProblemB::solveRegularisedQP ( const real_t *const  g_new,
const real_t *const  lb_new,
const real_t *const  ub_new,
int &  nWSR,
real_t *const  cputime,
int  nWSRperformed = 0 
)
private

Solves an initialised QProblemB using online active set strategy. Note: This function is internally called by all hotstart functions!

Returns
SUCCESSFUL_RETURN
RET_MAX_NWSR_REACHED
RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED
RET_HOTSTART_FAILED
RET_SHIFT_DETERMINATION_FAILED
RET_STEPDIRECTION_DETERMINATION_FAILED
RET_STEPLENGTH_DETERMINATION_FAILED
RET_HOMOTOPY_STEP_FAILED
RET_HOTSTART_STOPPED_INFEASIBILITY
RET_HOTSTART_STOPPED_UNBOUNDEDNESS
Parameters
g_newGradient of neighbouring QP to be solved.
lb_newLower bounds of neighbouring QP to be solved.
If no lower bounds exist, a NULL pointer can be passed.
ub_newUpper bounds of neighbouring QP to be solved.
If no upper bounds exist, a NULL pointer can be passed.
nWSRInput: Maximum number of working set recalculations;
Output: Number of performed working set recalculations.
cputimeInput: Maximum CPU time allowed for QP solution.
Output: CPU time spend for QP solution (or to perform nWSR iterations).
nWSRperformedNumber of working set recalculations already performed to solve this QP within previous solveRegularisedQP() calls. This number is always zero, except for successive calls when using the far bound strategy.

Definition at line 2579 of file external_packages/qpOASES-3.0beta/src/QProblemB.cpp.

returnValue QProblemB::updateFarBounds ( real_t  curFarBound,
int_t  nRamp,
const real_t *const  lb_new,
real_t *const  lb_new_far,
const real_t *const  ub_new,
real_t *const  ub_new_far 
) const
protected

...

Parameters
curFarBound...
nRamp...
lb_new...
lb_new_far...
ub_new...
ub_new_far...

Definition at line 2196 of file external_packages/qpOASES-3.2.0/src/QProblemB.cpp.

BooleanType QProblemB::usingRegularisation ( ) const
inline

Returns if the QP has been internally regularised.

Returns
BT_TRUE: Hessian is internally regularised for QP solution
BT_FALSE: No internal Hessian regularisation is used for QP solution
BooleanType QProblemB::usingRegularisation ( ) const
inline

Returns if the QP has been internally regularised.

Returns
BT_TRUE: Hessian is internally regularised for QP solution
BT_FALSE: No internal Hessian regularisation is used for QP solution

Friends And Related Function Documentation

Member Data Documentation

Bounds QProblemB::bounds
protected

Data structure for problem's bounds.

Definition at line 569 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/INCLUDE/QProblemB.hpp.

unsigned int QProblemB::count

Counts the number of hotstart function calls (internal usage only!).

Definition at line 90 of file QProblemB.h.

int QProblemB::count
protected

Counts the number of hotstart function calls (internal usage only!).

Definition at line 587 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/INCLUDE/QProblemB.hpp.

uint_t QProblemB::count
protected

Counts the number of hotstart function calls.

Definition at line 995 of file external_packages/qpOASES-3.2.0/include/qpOASES/QProblemB.hpp.

real_t QProblemB::delta_xFR_TMP[NVMAX]

Temporary for determineStepDirection

Definition at line 92 of file QProblemB.h.

real_t * QProblemB::delta_xFR_TMP
protected

Temporary for determineStepDirection

Definition at line 1025 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

Flipper QProblemB::flipper
protected

Struct for making a temporary copy of the matrix factorisations.

Definition at line 1032 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

BooleanType QProblemB::freeHessian
protected

Flag indicating whether the Hessian matrix needs to be de-allocated.

Definition at line 998 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

real_t QProblemB::g
protected
real_t* QProblemB::g
protected
DenseMatrix* QProblemB::H

Hessian matrix pointer.

Definition at line 65 of file QProblemB.h.

SymmetricMatrix * QProblemB::H
protected
SymmetricMatrix* QProblemB::H
protected

Hessian matrix.

Definition at line 999 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

BooleanType QProblemB::hasCholesky
protected

Flag indicating whether Cholesky decomposition has already been setup.

Definition at line 601 of file external_packages/qpoases/INCLUDE/QProblemB.hpp.

BooleanType QProblemB::hasHessian
protected

Flag indicating whether H contains Hessian or corresponding Cholesky factor R;

See also
init.

Definition at line 592 of file external_packages/qpoases/INCLUDE/QProblemB.hpp.

BooleanType QProblemB::haveCholesky
protected

Flag indicating whether Cholesky decomposition has already been setup.

Definition at line 1008 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

HessianType QProblemB::hessianType
protected
DenseMatrix QProblemB::HH

Hessian matrix.

Definition at line 66 of file QProblemB.h.

BooleanType QProblemB::infeasible
protected
BooleanType QProblemB::isRegularised
protected

Flag indicating whether Hessian matrix has been regularised.

Definition at line 1021 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

real_t QProblemB::lb
protected

Lower bound vector (on variables).

Definition at line 566 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/INCLUDE/QProblemB.hpp.

real_t* QProblemB::lb
protected

Lower bound vector (on variables).

Definition at line 1002 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

Options QProblemB::options
protected

Struct containing all user-defined options for solving QPs.

Definition at line 1030 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

PrintLevel QProblemB::printlevel
protected
real_t QProblemB::R
protected

Cholesky decomposition of H (i.e. H = R^T*R).

Cholesky factor of H (i.e. H = R^T*R).

Definition at line 571 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/INCLUDE/QProblemB.hpp.

real_t* QProblemB::R
protected

Cholesky factor of H (i.e. H = R^T*R).

Definition at line 1007 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

real_t QProblemB::ramp0
protected

Start value for Ramping Strategy (usually 0.5 or 1.0).

Start value for Ramping Strategy.

Definition at line 1027 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

real_t QProblemB::ramp1
protected

Final value for Ramping Strategy (usually 1.0 or 0.5).

Final value for Ramping Strategy.

Definition at line 1028 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

int QProblemB::rampOffset

Offset index for Ramping.

Definition at line 96 of file QProblemB.h.

int_t QProblemB::rampOffset
protected

Offset index for Ramping.

Definition at line 1001 of file external_packages/qpOASES-3.2.0/include/qpOASES/QProblemB.hpp.

real_t QProblemB::regVal
protected

Holds the offset used to regularise Hessian matrix (zero by default).

Definition at line 993 of file external_packages/qpOASES-3.2.0/include/qpOASES/QProblemB.hpp.

QProblemStatus QProblemB::status
protected

Current status of the solution process.

Definition at line 578 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/INCLUDE/QProblemB.hpp.

TabularOutput QProblemB::tabularOutput
protected

Struct storing information for tabular output (printLevel == PL_TABULAR).

Definition at line 1007 of file external_packages/qpOASES-3.2.0/include/qpOASES/QProblemB.hpp.

real_t QProblemB::tau
protected
real_t QProblemB::ub
protected

Upper bound vector (on variables).

Definition at line 567 of file examples/code_generation/mpc_mhe/getting_started_export/qpoases/INCLUDE/QProblemB.hpp.

real_t* QProblemB::ub
protected

Upper bound vector (on variables).

Definition at line 1003 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

BooleanType QProblemB::unbounded
protected
real_t QProblemB::x
protected
real_t* QProblemB::x
protected

Primal solution vector.

Definition at line 1010 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.

real_t QProblemB::y
protected
real_t* QProblemB::y
protected

Dual solution vector.

Definition at line 1011 of file external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp.


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


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