external_packages/qpOASES-3.0beta/include/qpOASES/QProblemB.hpp
Go to the documentation of this file.
1 /*
2  * This file is part of qpOASES.
3  *
4  * qpOASES -- An Implementation of the Online Active Set Strategy.
5  * Copyright (C) 2007-2011 by Hans Joachim Ferreau, Andreas Potschka,
6  * Christian Kirches et al. All rights reserved.
7  *
8  * qpOASES is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU Lesser General Public
10  * License as published by the Free Software Foundation; either
11  * version 2.1 of the License, or (at your option) any later version.
12  *
13  * qpOASES is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
16  * See the GNU Lesser General Public License for more details.
17  *
18  * You should have received a copy of the GNU Lesser General Public
19  * License along with qpOASES; if not, write to the Free Software
20  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
21  *
22  */
23 
24 
38 #ifndef QPOASES_QPROBLEMB_HPP
39 #define QPOASES_QPROBLEMB_HPP
40 
41 
42 #include <qpOASES/Flipper.hpp>
43 #include <qpOASES/Options.hpp>
44 #include <qpOASES/Matrices.hpp>
45 
46 
48 
49 
50 class SolutionAnalysis;
51 
63 class QProblemB
64 {
65  /* allow SolutionAnalysis class to access private members */
66  friend class SolutionAnalysis;
67 
68  /*
69  * PUBLIC MEMBER FUNCTIONS
70  */
71  public:
73  QProblemB( );
74 
80  QProblemB( int _nV,
81  HessianType _hessianType = HST_UNKNOWN
82  );
83 
85  QProblemB( const QProblemB& rhs
86  );
87 
89  virtual ~QProblemB( );
90 
93  );
94 
95 
99  virtual returnValue reset( );
100 
101 
114  const real_t* const _g,
115  const real_t* const _lb,
117  const real_t* const _ub,
119  int& nWSR,
121  real_t* const cputime
123  );
124 
136  returnValue init( const real_t* const _H,
138  const real_t* const _g,
139  const real_t* const _lb,
141  const real_t* const _ub,
143  int& nWSR,
145  real_t* const cputime
147  );
148 
160  returnValue init( const char* const H_file,
162  const char* const g_file,
163  const char* const lb_file,
165  const char* const ub_file,
167  int& nWSR,
169  real_t* const cputime
171  );
172 
192  const real_t* const _g,
193  const real_t* const _lb,
195  const real_t* const _ub,
197  int& nWSR,
199  real_t* const cputime,
201  const real_t* const xOpt,
203  const real_t* const yOpt,
205  const Bounds* const guessedBounds
207  );
208 
227  returnValue init( const real_t* const _H,
229  const real_t* const _g,
230  const real_t* const _lb,
232  const real_t* const _ub,
234  int& nWSR,
236  real_t* const cputime,
238  const real_t* const xOpt,
240  const real_t* const yOpt,
242  const Bounds* const guessedBounds
244  );
245 
264  returnValue init( const char* const H_file,
266  const char* const g_file,
267  const char* const lb_file,
269  const char* const ub_file,
271  int& nWSR,
273  real_t* const cputime,
275  const real_t* const xOpt,
277  const real_t* const yOpt,
279  const Bounds* const guessedBounds
281  );
282 
283 
297  returnValue hotstart( const real_t* const g_new,
298  const real_t* const lb_new,
300  const real_t* const ub_new,
302  int& nWSR,
304  real_t* const cputime
306  );
307 
324  returnValue hotstart( const char* const g_file,
325  const char* const lb_file,
327  const char* const ub_file,
329  int& nWSR,
331  real_t* const cputime
333  );
334 
349  returnValue hotstart( const real_t* const g_new,
350  const real_t* const lb_new,
352  const real_t* const ub_new,
354  int& nWSR,
356  real_t* const cputime,
358  const Bounds* const guessedBounds
360  );
361 
379  returnValue hotstart( const char* const g_file,
380  const char* const lb_file,
382  const char* const ub_file,
384  int& nWSR,
386  real_t* const cputime,
388  const Bounds* const guessedBounds
390  );
391 
392 
396  inline returnValue getBounds( Bounds& _bounds
397  ) const;
398 
399 
402  inline int getNV( ) const;
403 
406  inline int getNFR( ) const;
407 
410  inline int getNFX( ) const;
411 
414  inline int getNFV( ) const;
415 
418  virtual int getNZ( ) const;
419 
420 
424  real_t getObjVal( ) const;
425 
428  real_t getObjVal( const real_t* const _x
429  ) const;
430 
435  ) const;
436 
440  virtual returnValue getDualSolution( real_t* const yOpt
441  ) const;
442 
443 
446  inline QProblemStatus getStatus( ) const;
447 
448 
452  inline BooleanType isInitialised( ) const;
453 
457  inline BooleanType isSolved( ) const;
458 
462  inline BooleanType isInfeasible( ) const;
463 
467  inline BooleanType isUnbounded( ) const;
468 
469 
472  inline HessianType getHessianType( ) const;
473 
476  inline returnValue setHessianType( HessianType _hessianType
477  );
478 
482  inline BooleanType usingRegularisation( ) const;
483 
486  inline Options getOptions( ) const;
487 
490  inline returnValue setOptions( const Options& _options
491  );
492 
495  inline PrintLevel getPrintLevel( ) const;
496 
499  returnValue setPrintLevel( PrintLevel _printlevel
500  );
501 
502 
505  virtual returnValue printProperties( );
506 
509  returnValue printOptions( ) const;
510 
511 
512  /*
513  * PROTECTED MEMBER FUNCTIONS
514  */
515  protected:
518  returnValue clear( );
519 
522  returnValue copy( const QProblemB& rhs
523  );
524 
531 
535  virtual returnValue setupSubjectToType( );
536 
540  virtual returnValue setupSubjectToType( const real_t* const lb_new,
541  const real_t* const ub_new
542  );
543 
553 
554 
562  const real_t* const yOpt,
564  const Bounds* const guessedBounds,
565  Bounds* auxiliaryBounds
567  ) const;
568 
569 
573  returnValue backsolveR( const real_t* const b,
574  BooleanType transposed,
575  real_t* const a
576  ) const;
577 
582  returnValue backsolveR( const real_t* const b,
583  BooleanType transposed,
584  BooleanType removingBound,
585  real_t* const a
586  ) const;
587 
588 
592  const real_t* const lb_new,
593  const real_t* const ub_new,
594  real_t* const delta_g,
595  real_t* const delta_lb,
596  real_t* const delta_ub,
597  BooleanType& Delta_bB_isZero
598  );
599 
600 
605  const real_t* const _g,
606  const real_t* const _lb,
608  const real_t* const _ub
610  );
611 
618  returnValue setupQPdata( const real_t* const _H,
620  const real_t* const _g,
621  const real_t* const _lb,
623  const real_t* const _ub
625  );
626 
635  returnValue setupQPdataFromFile( const char* const H_file,
637  const char* const g_file,
638  const char* const lb_file,
640  const char* const ub_file
642  );
643 
649  returnValue loadQPvectorsFromFile( const char* const g_file,
650  const char* const lb_file,
652  const char* const ub_file,
654  real_t* const g_new,
655  real_t* const lb_new,
656  real_t* const ub_new
657  ) const;
658 
659 
666  );
667 
668 
672  BooleanType isCPUtimeLimitExceeded( const real_t* const cputime,
673  real_t starttime,
674  int nWSR
675  ) const;
676 
677 
682 
683 
687  );
688 
694  inline returnValue setH( const real_t* const H_new
695  );
696 
700  inline returnValue setG( const real_t* const g_new
701  );
702 
706  inline returnValue setLB( const real_t* const lb_new
707  );
708 
712  inline returnValue setLB( int number,
713  real_t value
714  );
715 
719  inline returnValue setUB( const real_t* const ub_new
720  );
721 
725  inline returnValue setUB( int number,
726  real_t value
727  );
728 
729 
732  inline void computeGivens( real_t xold,
733  real_t yold,
734  real_t& xnew,
735  real_t& ynew,
736  real_t& c,
737  real_t& s
738  ) const;
739 
742  inline void applyGivens( real_t c,
743  real_t s,
744  real_t nu,
745  real_t xold,
747  real_t yold,
749  real_t& xnew,
751  real_t& ynew
753  ) const;
754 
755 
756 
760  real_t relativeHomotopyLength( const real_t* const g_new,
761  const real_t* const lb_new,
762  const real_t* const ub_new
763  );
764 
768  virtual returnValue performRamping( );
769 
770 
774  returnValue performRatioTest( int nIdx,
775  const int* const idxList,
776  const SubjectTo* const subjectTo,
777  const real_t* const num,
778  const real_t* const den,
779  real_t epsNum,
780  real_t epsDen,
781  real_t& t,
782  int& BC_idx
783  ) const;
784 
788  inline BooleanType isBlocking( real_t num,
789  real_t den,
790  real_t epsNum,
791  real_t epsDen,
792  real_t& t
794  ) const;
795 
796 
797  /*
798  * PRIVATE MEMBER FUNCTIONS
799  */
800  private:
812  returnValue solveInitialQP( const real_t* const xOpt,
814  const real_t* const yOpt,
816  const Bounds* const guessedBounds,
818  int& nWSR,
820  real_t* const cputime
822  );
823 
836  returnValue solveQP( const real_t* const g_new,
837  const real_t* const lb_new,
839  const real_t* const ub_new,
841  int& nWSR,
843  real_t* const cputime,
845  int nWSRperformed = 0
849  );
850 
851 
865  const real_t* const lb_new,
867  const real_t* const ub_new,
869  int& nWSR,
871  real_t* const cputime,
873  int nWSRperformed = 0
876  );
877 
878 
886  returnValue setupAuxiliaryWorkingSet( const Bounds* const auxiliaryBounds,
887  BooleanType setupAfresh
889  );
890 
895  const real_t* const yOpt
897  );
898 
904 
911  );
912 
913 
919  returnValue setupAuxiliaryQP( const Bounds* const guessedBounds
920  );
921 
925  returnValue determineStepDirection( const real_t* const delta_g,
926  const real_t* const delta_lb,
927  const real_t* const delta_ub,
928  BooleanType Delta_bB_isZero,
929  real_t* const delta_xFX,
930  real_t* const delta_xFR,
931  real_t* const delta_yFX
932  );
933 
939  returnValue performStep( const real_t* const delta_g,
940  const real_t* const delta_lb,
941  const real_t* const delta_ub,
942  const real_t* const delta_xFX,
943  const real_t* const delta_xFR,
944  const real_t* const delta_yFX,
945  int& BC_idx,
946  SubjectToStatus& BC_status
947  );
948 
953  returnValue changeActiveSet( int BC_idx,
954  SubjectToStatus BC_status
955  );
956 
960 
965  BooleanType shallRefactorise( const Bounds* const guessedBounds
966  ) const;
967 
968 
972  returnValue addBound( int number,
973  SubjectToStatus B_status,
974  BooleanType updateCholesky
975  );
976 
981  returnValue removeBound( int number,
982  BooleanType updateCholesky
983  );
984 
985 
988  returnValue printIteration( int iteration,
989  int BC_idx,
990  SubjectToStatus BC_status
991  );
992 
993 
994  /*
995  * PROTECTED MEMBER VARIABLES
996  */
997  protected:
1005  Bounds bounds;
1013  real_t tau;
1023  int count;
1033 };
1034 
1035 
1037 
1038 #include <qpOASES/QProblemB.ipp>
1039 
1040 #endif /* QPOASES_QPROBLEMB_HPP */
1041 
1042 
1043 /*
1044  * end of file
1045  */
HessianType getHessianType() const
BooleanType isInfeasible() const
returnValue copy(const QProblemB &rhs)
Implements the online active set strategy for box-constrained QPs.
int getNFV() const
BooleanType isUnbounded() const
int getNFX()
void computeGivens(real_t xold, real_t yold, real_t &xnew, real_t &ynew, real_t &c, real_t &s) const
returnValue obtainAuxiliaryWorkingSet(const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds, Bounds *auxiliaryBounds) const
BooleanType shallRefactorise(const Bounds *const guessedBounds) const
Allows to pass back messages to the calling function.
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)
Base class for managing working sets of bounds and constraints.
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 setupAuxiliaryWorkingSet(const Bounds *const auxiliaryBounds, BooleanType setupAfresh)
returnValue getBounds(Bounds *const _bounds) const
int getNV() const
returnValue setH(const real_t *const H_new)
returnValue setInfeasibilityFlag(returnValue returnvalue)
returnValue setupAuxiliaryQPsolution(const real_t *const xOpt, const real_t *const yOpt)
returnValue backsolveR(const real_t *const b, BooleanType transposed, real_t *const a)
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)
Auxiliary class for storing a copy of the current matrix factorisations.
Options getOptions() const
returnValue setOptions(const Options &_options)
returnValue changeActiveSet(int BC_idx, SubjectToStatus BC_status)
BooleanType usingRegularisation() const
real_t relativeHomotopyLength(const real_t *const g_new, const real_t *const lb_new, const real_t *const ub_new)
BooleanType isCPUtimeLimitExceeded(const real_t *const cputime, real_t starttime, int nWSR) const
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 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
BooleanType isBlocking(real_t num, real_t den, real_t epsNum, real_t epsDen, real_t &t) const
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 addBound(int number, SubjectToStatus B_status, BooleanType updateCholesky)
returnValue setupQPdata(const real_t *const _H, const real_t *const _g, const real_t *const _lb, const real_t *const _ub)
const int nu
returnValue printIteration(int iteration, int BC_idx, SubjectToStatus BC_status)
Provides a generic way to set and pass user-specified options.
Definition: options.hpp:65
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)
PrintLevel getPrintLevel() const
int getNFR()
returnValue setupQPdataFromFile(const char *const H_file, const char *const g_file, const char *const lb_file, const char *const ub_file)
returnValue setHessianType(HessianType _hessianType)
void rhs(const real_t *x, real_t *f)
PrintLevel
returnValue setupAuxiliaryQP(const Bounds *const guessedBounds)
BooleanType isInitialised() const
QProblemStatus getStatus() const
returnValue setUB(const real_t *const ub_new)
returnValue setG(const real_t *const g_new)
#define HST_UNKNOWN
returnValue removeBound(int number, BooleanType updateCholesky)
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)
Manages working sets of bounds (= box constraints).
double real_t
Definition: AD_test.c:10
void applyGivens(real_t c, real_t s, real_t xold, real_t yold, real_t &xnew, real_t &ynew) 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 solveInitialQP(const real_t *const xOpt, const real_t *const yOpt, const Bounds *const guessedBounds, int &nWSR, real_t *const cputime)
returnValue setLB(const real_t *const lb_new)
Abstract base class for interfacing matrix-vector operations tailored to symmetric matrices...
BooleanType isSolved() const


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