QProblem.hpp
Go to the documentation of this file.
00001 /*
00002  *      This file is part of qpOASES.
00003  *
00004  *      qpOASES -- An Implementation of the Online Active Set Strategy.
00005  *      Copyright (C) 2007-2011 by Hans Joachim Ferreau, Andreas Potschka,
00006  *      Christian Kirches et al. All rights reserved.
00007  *
00008  *      qpOASES is free software; you can redistribute it and/or
00009  *      modify it under the terms of the GNU Lesser General Public
00010  *      License as published by the Free Software Foundation; either
00011  *      version 2.1 of the License, or (at your option) any later version.
00012  *
00013  *      qpOASES is distributed in the hope that it will be useful,
00014  *      but WITHOUT ANY WARRANTY; without even the implied warranty of
00015  *      MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
00016  *      See the GNU Lesser General Public License for more details.
00017  *
00018  *      You should have received a copy of the GNU Lesser General Public
00019  *      License along with qpOASES; if not, write to the Free Software
00020  *      Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
00021  *
00022  */
00023 
00024 
00037 #ifndef QPOASES_QPROBLEM_HPP
00038 #define QPOASES_QPROBLEM_HPP
00039 
00040 
00041 #include <qpOASES/QProblemB.hpp>
00042 #include <qpOASES/Constraints.hpp>
00043 #include <qpOASES/ConstraintProduct.hpp>
00044 #include <qpOASES/Matrices.hpp>
00045 
00046 
00047 BEGIN_NAMESPACE_QPOASES
00048 
00049 
00061 class QProblem : public QProblemB
00062 {
00063         /* allow SolutionAnalysis class to access private members */
00064         friend class SolutionAnalysis;
00065 
00066         /*
00067          *      PUBLIC MEMBER FUNCTIONS
00068          */
00069         public:
00071                 QProblem( );
00072 
00078                 QProblem(       int _nV,                                                                
00079                                         int _nC,                                                                
00080                                         HessianType _hessianType = HST_UNKNOWN  
00081                                         );
00082 
00084                 QProblem(       const QProblem& rhs             
00085                                         );
00086 
00088                 virtual ~QProblem( );
00089 
00091                 QProblem& operator=(    const QProblem& rhs     
00092                                                                 );
00093 
00094 
00098                 virtual returnValue reset( );
00099 
00100 
00113                 returnValue init(       SymmetricMatrix *_H,            
00114                                                         const real_t* const _g,         
00115                                                         Matrix *_A,                             
00116                                                         const real_t* const _lb,        
00118                                                         const real_t* const _ub,        
00120                                                         const real_t* const _lbA,       
00122                                                         const real_t* const _ubA,       
00124                                                         int& nWSR,                                      
00126                                                         real_t* const cputime           
00128                                                         );
00129 
00130 
00143                 returnValue init(       const real_t* const _H,         
00145                                                         const real_t* const _g,         
00146                                                         const real_t* const _A,         
00147                                                         const real_t* const _lb,        
00149                                                         const real_t* const _ub,        
00151                                                         const real_t* const _lbA,       
00153                                                         const real_t* const _ubA,       
00155                                                         int& nWSR,                                      
00157                                                         real_t* const cputime           
00159                                                         );
00160 
00173                 returnValue init(       const char* const H_file,       
00175                                                         const char* const g_file,       
00176                                                         const char* const A_file,       
00177                                                         const char* const lb_file,      
00179                                                         const char* const ub_file,      
00181                                                         const char* const lbA_file,     
00183                                                         const char* const ubA_file,     
00185                                                         int& nWSR,                                      
00187                                                         real_t* const cputime           
00189                                                         );
00190 
00210                 returnValue init(       SymmetricMatrix *_H,                                            
00211                                                         const real_t* const _g,                                         
00212                                                         Matrix *_A,                                                             
00213                                                         const real_t* const _lb,                                        
00215                                                         const real_t* const _ub,                                        
00217                                                         const real_t* const _lbA,                                       
00219                                                         const real_t* const _ubA,                                       
00221                                                         int& nWSR,                                                                      
00223                                                         real_t* const cputime,                                          
00225                                                         const real_t* const xOpt,                                       
00227                                                         const real_t* const yOpt,                                       
00229                                                         const Bounds* const guessedBounds,                      
00230                                                         const Constraints* const guessedConstraints     
00231                                                         );
00232 
00252                 returnValue init(       const real_t* const _H,                                         
00254                                                         const real_t* const _g,                                         
00255                                                         const real_t* const _A,                                         
00256                                                         const real_t* const _lb,                                        
00258                                                         const real_t* const _ub,                                        
00260                                                         const real_t* const _lbA,                                       
00262                                                         const real_t* const _ubA,                                       
00264                                                         int& nWSR,                                                                      
00266                                                         real_t* const cputime,                                          
00268                                                         const real_t* const xOpt,                                       
00270                                                         const real_t* const yOpt,                                       
00272                                                         const Bounds* const guessedBounds,                      
00273                                                         const Constraints* const guessedConstraints     
00274                                                         );
00275 
00295                 returnValue init(       const char* const H_file,                                       
00297                                                         const char* const g_file,                                       
00298                                                         const char* const A_file,                                       
00299                                                         const char* const lb_file,                                      
00301                                                         const char* const ub_file,                                      
00303                                                         const char* const lbA_file,                                     
00305                                                         const char* const ubA_file,                                     
00307                                                         int& nWSR,                                                                      
00309                                                         real_t* const cputime,                                          
00311                                                         const real_t* const xOpt,                                       
00313                                                         const real_t* const yOpt,                                       
00315                                                         const Bounds* const guessedBounds,                      
00316                                                         const Constraints* const guessedConstraints     
00317                                                         );
00318 
00319 
00333                 returnValue hotstart(   const real_t* const g_new,              
00334                                                                 const real_t* const lb_new,             
00336                                                                 const real_t* const ub_new,             
00338                                                                 const real_t* const lbA_new,    
00340                                                                 const real_t* const ubA_new,    
00342                                                                 int& nWSR,                                              
00344                                                                 real_t* const cputime                   
00346                                                                 );
00347 
00364                 returnValue hotstart(   const char* const g_file,       
00365                                                                 const char* const lb_file,      
00367                                                                 const char* const ub_file,      
00369                                                                 const char* const lbA_file, 
00371                                                                 const char* const ubA_file, 
00373                                                                 int& nWSR,                                      
00375                                                                 real_t* const cputime                   
00377                                                                 );
00378 
00393                 returnValue hotstart(   const real_t* const g_new,                                      
00394                                                                 const real_t* const lb_new,                                     
00396                                                                 const real_t* const ub_new,                                     
00398                                                                 const real_t* const lbA_new,                            
00400                                                                 const real_t* const ubA_new,                            
00402                                                                 int& nWSR,                                                                      
00404                                                                 real_t* const cputime,                                          
00406                                                                 const Bounds* const guessedBounds,                      
00408                                                                 const Constraints* const guessedConstraints     
00410                                                                 );
00411 
00429                 returnValue hotstart(   const char* const g_file,                                       
00430                                                                 const char* const lb_file,                                      
00432                                                                 const char* const ub_file,                                      
00434                                                                 const char* const lbA_file,                             
00436                                                                 const char* const ubA_file,                             
00438                                                                 int& nWSR,                                                                      
00440                                                                 real_t* const cputime,                                          
00442                                                                 const Bounds* const guessedBounds,                      
00444                                                                 const Constraints* const guessedConstraints     
00446                                                                 );
00447 
00452         returnValue solveCurrentEQP (   const int n_rhs,                        
00453                                                                                 const real_t* g_in,                     
00454                                                                                 const real_t* lb_in,            
00456                                                                                 const real_t* ub_in,            
00458                                                                                 const real_t* lbA_in,           
00460                                                                                 const real_t* ubA_in,           
00461                                                                                 real_t* x_out,                          
00462                                                                                 real_t* y_out                           
00463                                                                                 );
00464 
00465 
00469                 inline returnValue getConstraints(      Constraints& _constraints       
00470                                                                                         ) const;
00471 
00472 
00475                 inline int getNC( ) const;
00476 
00479                 inline int getNEC( ) const;
00480 
00483                 inline int getNAC( ) const;
00484 
00487                 inline int getNIAC( ) const;
00488 
00491                 virtual int getNZ( ) const;
00492 
00493 
00497                 virtual returnValue getDualSolution(    real_t* const yOpt      
00498                                                                                                 ) const;
00499 
00500 
00503                 returnValue setConstraintProduct(       ConstraintProduct* const _constraintProduct
00504                                                                                         );
00505 
00506 
00509                 virtual returnValue printProperties( );
00510 
00511 
00512         /*
00513          *      PROTECTED MEMBER FUNCTIONS
00514          */
00515         protected:
00518                 returnValue clear( );
00519 
00522                 returnValue copy(       const QProblem& rhs     
00523                                                         );
00524 
00537                 returnValue solveInitialQP(     const real_t* const xOpt,                                               
00539                                                                         const real_t* const yOpt,                                               
00541                                                                         const Bounds* const guessedBounds,                              
00543                                                                         const Constraints* const guessedConstraints,    
00545                                                                         int& nWSR,                                                                              
00547                                                                         real_t* const cputime                                                   
00549                                                                         );
00550 
00563                 returnValue solveQP(    const real_t* const g_new,              
00564                                                                 const real_t* const lb_new,     
00566                                                                 const real_t* const ub_new,             
00568                                                                 const real_t* const lbA_new,    
00570                                                                 const real_t* const ubA_new,    
00572                                                                 int& nWSR,                                              
00574                                                                 real_t* const cputime,                  
00576                                                                 int  nWSRperformed = 0                  
00580                                                                 );
00581 
00582 
00595                 returnValue solveRegularisedQP( const real_t* const g_new,              
00596                                                                                 const real_t* const lb_new,             
00598                                                                                 const real_t* const ub_new,             
00600                                                                                 const real_t* const lbA_new,    
00602                                                                                 const real_t* const ubA_new,    
00604                                                                                 int& nWSR,                                              
00606                                                                                 real_t* const cputime,                  
00608                                                                                 int  nWSRperformed = 0                  
00611                                                                                 );
00612 
00613 
00617                 virtual returnValue setupSubjectToType( );
00618 
00622                 virtual returnValue setupSubjectToType( const real_t* const lb_new,             
00623                                                                                                 const real_t* const ub_new,             
00624                                                                                                 const real_t* const lbA_new,    
00625                                                                                                 const real_t* const ubA_new             
00626                                                                                                 );
00627 
00634                 returnValue setupCholeskyDecompositionProjected( );
00635 
00641                 returnValue computeInitialCholesky( );
00642 
00646                 returnValue setupTQfactorisation( );
00647 
00648 
00655                 returnValue obtainAuxiliaryWorkingSet(  const real_t* const xOpt,                                               
00657                                                                                                 const real_t* const yOpt,                                               
00659                                                                                                 const Bounds* const guessedBounds,                              
00660                                                                                                 const Constraints* const guessedConstraints,    
00661                                                                                                 Bounds* auxiliaryBounds,                                                
00663                                                                                                 Constraints* auxiliaryConstraints                               
00665                                                                                                 ) const;
00666 
00675                 returnValue setupAuxiliaryWorkingSet(   const Bounds* const auxiliaryBounds,                    
00676                                                                                                 const Constraints* const auxiliaryConstraints,  
00677                                                                                                 BooleanType setupAfresh                                                 
00679                                                                                                 );
00680 
00683                 returnValue setupAuxiliaryQPsolution(   const real_t* const xOpt,                       
00685                                                                                                 const real_t* const yOpt                        
00687                                                                                                 );
00688 
00693                 returnValue setupAuxiliaryQPgradient( );
00694 
00700                 returnValue setupAuxiliaryQPbounds(     const Bounds* const auxiliaryBounds,                    
00701                                                                                         const Constraints* const auxiliaryConstraints,  
00702                                                                                         BooleanType useRelaxation                                               
00703                                                                                         );
00704 
00705 
00711                 returnValue addConstraint(      int number,                                     
00712                                                                         SubjectToStatus C_status,       
00713                                                                         BooleanType updateCholesky,     
00714                                                                         BooleanType ensureLI = BT_TRUE  
00715                                                                         );
00716 
00722                 returnValue addConstraint_checkLI(      int number                      
00723                                                                                         );
00724 
00733                 returnValue addConstraint_ensureLI(     int number,                                     
00734                                                                                         SubjectToStatus C_status        
00735                                                                                         );
00736 
00742                 returnValue addBound(   int number,                                     
00743                                                                 SubjectToStatus B_status,       
00744                                                                 BooleanType updateCholesky,     
00745                                                                 BooleanType ensureLI = BT_TRUE  
00746                                                                 );
00747 
00752                 returnValue addBound_checkLI(   int number                      
00753                                                                                 );
00754 
00763                 returnValue addBound_ensureLI(  int number,                                     
00764                                                                                 SubjectToStatus B_status        
00765                                                                                 );
00766 
00772                 returnValue removeConstraint(   int number,                                                             
00773                                                                                 BooleanType updateCholesky,                             
00774                                                                                 BooleanType allowFlipping = BT_FALSE,   
00775                                                                                 BooleanType ensureNZC = BT_FALSE                
00776                                                                                 );
00777 
00783                 returnValue removeBound(        int number,                                                             
00784                                                                         BooleanType updateCholesky,                             
00785                                                                         BooleanType allowFlipping = BT_FALSE,   
00786                                                                         BooleanType ensureNZC = BT_FALSE                
00787                                                                         );
00788 
00789 
00793                 returnValue performPlainRatioTest(      int nIdx,                                                       
00794                                                                                         const int* const idxList,                       
00795                                                                                         const real_t* const num,                        
00796                                                                                         const real_t* const den,                        
00797                                                                                         real_t epsNum,                                          
00798                                                                                         real_t epsDen,                                          
00799                                                                                         real_t& t,                                                      
00800                                                                                         int& BC_idx                                             
00801                                                                                         ) const;
00802 
00803 
00807                 returnValue ensureNonzeroCurvature(
00808                                 BooleanType removeBoundNotConstraint,   
00809                                 int remIdx,                                                             
00810                                 BooleanType &exchangeHappened,                  
00811                                 BooleanType &addBoundNotConstraint,             
00812                                 int &addIdx,                                                    
00813                                 SubjectToStatus &addStatus                              
00814                                 );
00815 
00816 
00820                 returnValue backsolveT( const real_t* const b,  
00821                                                                 BooleanType transposed, 
00822                                                                 real_t* const a                 
00823                                                                 ) const;
00824 
00825 
00828                 returnValue determineDataShift( const real_t* const g_new,      
00829                                                                                 const real_t* const lbA_new,
00830                                                                                 const real_t* const ubA_new,
00831                                                                                 const real_t* const lb_new,     
00832                                                                                 const real_t* const ub_new,     
00833                                                                                 real_t* const delta_g,          
00834                                                                                 real_t* const delta_lbA,        
00835                                                                                 real_t* const delta_ubA,        
00836                                                                                 real_t* const delta_lb,         
00837                                                                                 real_t* const delta_ub,         
00838                                                                                 BooleanType& Delta_bC_isZero,
00839                                                                                 BooleanType& Delta_bB_isZero
00840                                                                                 );
00841 
00846                 returnValue determineStepDirection(     const real_t* const delta_g,    
00847                                                                                         const real_t* const delta_lbA,  
00848                                                                                         const real_t* const delta_ubA,  
00849                                                                                         const real_t* const delta_lb,   
00850                                                                                         const real_t* const delta_ub,   
00851                                                                                         BooleanType Delta_bC_isZero,    
00852                                                                                         BooleanType Delta_bB_isZero,    
00853                                                                                         real_t* const delta_xFX,                
00854                                                                                         real_t* const delta_xFR,                
00855                                                                                         real_t* const delta_yAC,                
00856                                                                                         real_t* const delta_yFX                 
00857                                                                                         );
00858 
00864                 returnValue performStep(        const real_t* const delta_g,            
00865                                                                         const real_t* const delta_lbA,          
00866                                                                         const real_t* const delta_ubA,          
00867                                                                         const real_t* const delta_lb,           
00868                                                                         const real_t* const delta_ub,           
00869                                                                         const real_t* const delta_xFX,          
00870                                                                         const real_t* const delta_xFR,          
00871                                                                         const real_t* const delta_yAC,          
00872                                                                         const real_t* const delta_yFX,          
00873                                                                         int& BC_idx,                                            
00874                                                                         SubjectToStatus& BC_status,                     
00875                                                                         BooleanType& BC_isBound                         
00876                                                                         );
00877 
00882                 returnValue changeActiveSet(    int BC_idx,                                             
00883                                                                                 SubjectToStatus BC_status,                      
00884                                                                                 BooleanType BC_isBound                          
00885                                                                                 );
00886 
00887 
00891                 real_t relativeHomotopyLength(  const real_t* const g_new,              
00892                                                                                 const real_t* const lb_new,             
00893                                                                                 const real_t* const ub_new,             
00894                                                                                 const real_t* const lbA_new,    
00895                                                                                 const real_t* const ubA_new             
00896                                                                                 );
00897 
00898 
00902                 virtual returnValue performRamping( );
00903 
00904 
00907                 returnValue performDriftCorrection( );
00908 
00909 
00916                 virtual returnValue setupAuxiliaryQP(   const Bounds* const guessedBounds,                      
00917                                                                                                 const Constraints* const guessedConstraints     
00918                                                                                                 );
00919 
00924                 BooleanType shallRefactorise(   const Bounds* const guessedBounds,                      
00925                                                                                 const Constraints* const guessedConstraints     
00926                                                                                 ) const;
00927 
00932                 returnValue setupQPdata(        SymmetricMatrix *_H,            
00934                                                                         const real_t* const _g,         
00935                                                                         Matrix *_A,                             
00936                                                                         const real_t* const _lb,        
00938                                                                         const real_t* const _ub,        
00940                                                                         const real_t* const _lbA,       
00942                                                                         const real_t* const _ubA        
00944                                                                         );
00945 
00946 
00953                 returnValue setupQPdata(        const real_t* const _H,         
00955                                                                         const real_t* const _g,         
00956                                                                         const real_t* const _A,         
00957                                                                         const real_t* const _lb,        
00959                                                                         const real_t* const _ub,        
00961                                                                         const real_t* const _lbA,       
00963                                                                         const real_t* const _ubA        
00965                                                                         );
00966 
00975                 returnValue setupQPdataFromFile(        const char* const H_file,       
00977                                                                                         const char* const g_file,       
00978                                                                                         const char* const A_file,       
00979                                                                                         const char* const lb_file,      
00981                                                                                         const char* const ub_file,      
00983                                                                                         const char* const lbA_file, 
00985                                                                                         const char* const ubA_file      
00987                                                                                         );
00988 
00994                 returnValue loadQPvectorsFromFile(      const char* const g_file,       
00995                                                                                         const char* const lb_file,      
00997                                                                                         const char* const ub_file,      
00999                                                                                         const char* const lbA_file, 
01001                                                                                         const char* const ubA_file, 
01003                                                                                         real_t* const g_new,            
01004                                                                                         real_t* const lb_new,           
01005                                                                                         real_t* const ub_new,           
01006                                                                                         real_t* const lbA_new,          
01007                                                                                         real_t* const ubA_new           
01008                                                                                         ) const;
01009 
01010 
01013                 returnValue printIteration(     int iteration,                          
01014                                                                         int BC_idx,                             
01015                                                                         SubjectToStatus BC_status,      
01016                                                                         BooleanType BC_isBound          
01017                                                                         );
01018 
01019 
01024                 inline returnValue setA(        Matrix *A_new   
01025                                                                         );
01026 
01031                 inline returnValue setA(        const real_t* const A_new       
01032                                                                         );
01033 
01034 
01038                 inline returnValue setLBA(      const real_t* const lbA_new     
01039                                                                         );
01040 
01044                 inline returnValue setLBA(      int number,             
01045                                                                         real_t value    
01046                                                                         );
01047 
01051                 inline returnValue setUBA(      const real_t* const ubA_new     
01052                                                                         );
01053 
01057                 inline returnValue setUBA(      int number,             
01058                                                                         real_t value    
01059                                                                         );
01060 
01061         /*
01062          *      PROTECTED MEMBER VARIABLES
01063          */
01064         protected:
01065                 BooleanType freeConstraintMatrix;               
01066                 Matrix* A;                                                              
01068                 real_t* lbA;                                                    
01069                 real_t* ubA;                                                    
01071                 Constraints constraints;                                
01073                 real_t* T;                                                              
01074                 real_t* Q;                                                              
01075                 int sizeT;                                                              
01077                 real_t* Ax;                                                             
01079                 real_t* Ax_l;                                                   
01081                 real_t* Ax_u;                                                   
01084                 ConstraintProduct* constraintProduct;   
01086                 real_t* tempA;                                                  
01087                 real_t* tempB;                                                  
01088                 real_t* ZFR_delta_xFRz;                                 
01089                 real_t* delta_xFRy;                                             
01090                 real_t* delta_xFRz;                                             
01091                 real_t* delta_yAC_TMP;                                  
01093                 int idxAddB;                                                    
01094                 int idxRemB;                                                    
01095                 int idxAddC;                                                    
01096                 int idxRemC;                                                    
01097 };
01098 
01099 
01100 END_NAMESPACE_QPOASES
01101 
01102 #include <qpOASES/QProblem.ipp>
01103 
01104 #endif  /* QPOASES_QPROBLEM_HPP */
01105 
01106 
01107 /*
01108  *      end of file
01109  */


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Thu Aug 27 2015 11:59:50