qp_solver_qpoases.hpp
Go to the documentation of this file.
00001 /*
00002  *    This file is part of ACADO Toolkit.
00003  *
00004  *    ACADO Toolkit -- A Toolkit for Automatic Control and Dynamic Optimization.
00005  *    Copyright (C) 2008-2014 by Boris Houska, Hans Joachim Ferreau,
00006  *    Milan Vukov, Rien Quirynen, KU Leuven.
00007  *    Developed within the Optimization in Engineering Center (OPTEC)
00008  *    under supervision of Moritz Diehl. All rights reserved.
00009  *
00010  *    ACADO Toolkit is free software; you can redistribute it and/or
00011  *    modify it under the terms of the GNU Lesser General Public
00012  *    License as published by the Free Software Foundation; either
00013  *    version 3 of the License, or (at your option) any later version.
00014  *
00015  *    ACADO Toolkit is distributed in the hope that it will be useful,
00016  *    but WITHOUT ANY WARRANTY; without even the implied warranty of
00017  *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00018  *    Lesser General Public License for more details.
00019  *
00020  *    You should have received a copy of the GNU Lesser General Public
00021  *    License along with ACADO Toolkit; if not, write to the Free Software
00022  *    Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
00023  *
00024  */
00025 
00026 
00034 #ifndef ACADO_TOOLKIT_QP_SOLVER_QPOASES_HPP
00035 #define ACADO_TOOLKIT_QP_SOLVER_QPOASES_HPP
00036 
00037 
00038 #include <acado/conic_solver/dense_qp_solver.hpp>
00039 
00040 namespace qpOASES
00041 {
00042         class SQProblem;
00043 }
00044 
00045 BEGIN_NAMESPACE_ACADO
00046 
00057 class QPsolver_qpOASES : public DenseQPsolver
00058 {
00059     //
00060     // PUBLIC MEMBER FUNCTIONS:
00061     //
00062     public:
00064         QPsolver_qpOASES( );
00065                 
00066         QPsolver_qpOASES(       UserInteraction* _userInteraction
00067                                                         );
00068 
00070         QPsolver_qpOASES( const QPsolver_qpOASES& rhs );
00071 
00073         virtual ~QPsolver_qpOASES( );
00074 
00076         QPsolver_qpOASES& operator=( const QPsolver_qpOASES& rhs );
00077 
00078 
00079         virtual DenseCPsolver* clone( ) const;
00080 
00081         virtual DenseQPsolver* cloneDenseQPsolver( ) const;
00082 
00083 
00085         virtual returnValue solve( DenseCP *cp_  );
00086 
00087 
00093         virtual returnValue solve(      double* H,      
00094                                                                         double* A,      
00095                                                                         double* g,      
00096                                                                         double* lb,     
00097                                                                         double* ub,     
00098                                                                         double* lbA,    
00099                                                                         double* ubA,    
00100                                                                         uint maxIter            
00101                                                                         );
00102 
00104         virtual returnValue solve(  DMatrix *H,    
00105                                     DMatrix *A,    
00106                                     DVector *g,    
00107                                     DVector *lb,   
00108                                     DVector *ub,   
00109                                     DVector *lbA,  
00110                                     DVector *ubA,  
00111                                     uint maxIter        
00112                                                                         );
00113 
00114 
00120         virtual returnValue step(       double* H,              
00121                                                                         double* A,              
00122                                                                         double* g,              
00123                                                                         double* lb,             
00124                                                                         double* ub,             
00125                                                                         double* lbA,    
00126                                                                         double* ubA     
00127                                                                         );
00128 
00134         virtual returnValue step(       DMatrix *H,    
00135                                     DMatrix *A,    
00136                                     DVector *g,    
00137                                     DVector *lb,   
00138                                     DVector *ub,   
00139                                     DVector *lbA,  
00140                                     DVector *ubA   
00141                                                                         );
00142 
00143 
00147                 virtual returnValue getPrimalSolution(  DVector& xOpt   
00148                                                                                                 ) const;
00149 
00153                 virtual returnValue getDualSolution(    DVector& yOpt   
00154                                                                                                 ) const;
00155 
00160                 virtual double getObjVal( ) const;
00161 
00162 
00163                 virtual uint getNumberOfVariables( ) const;
00164                 virtual uint getNumberOfConstraints( ) const;
00165 
00166 
00172         virtual returnValue getVarianceCovariance( DMatrix &var );
00173 
00174 
00180         virtual returnValue getVarianceCovariance( DMatrix &H, DMatrix &var );
00181 
00182 
00183 
00184     //
00185     // PROTECTED MEMBER FUNCTIONS:
00186     //
00187     protected:
00191         virtual returnValue setupQPobject(      uint nV,        
00192                                                                                         uint nC         
00193                                                                                         );
00194 
00195                 returnValue updateQPstatus(     int ret
00196                                                                         );
00197 
00198 
00199 
00200     //
00201     // DATA MEMBERS:
00202     //
00203     protected:
00204                 qpOASES::SQProblem* qp;
00205 };
00206 
00207 
00208 CLOSE_NAMESPACE_ACADO
00209 
00210 
00211 #include <acado/bindings/acado_qpoases/qp_solver_qpoases.ipp>
00212 
00213 
00214 #endif  // ACADO_TOOLKIT_QP_SOLVER_QPOASES_HPP
00215 
00216 /*
00217  *      end of file
00218  */


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