model_data.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 
00033 #ifndef ACADO_TOOLKIT_MODELDATA_HPP
00034 #define ACADO_TOOLKIT_MODELDATA_HPP
00035 
00036 #include <acado/function/function.hpp>
00037 
00038 
00039 BEGIN_NAMESPACE_ACADO
00040 
00041 
00052 class ModelData {
00053 
00054 
00055 //
00056 // PUBLIC MEMBER FUNCTIONS:
00057 //
00058 public:
00059 
00060 
00064         ModelData( );
00065 
00066 
00082         returnValue setDimensions( uint _NX1, uint _NX2, uint _NX3, uint _NDX, uint _NDX3, uint _NXA, uint _NXA3, uint _NU, uint _NOD, uint _NP );
00083 
00084 
00092         uint addOutput( const OutputFcn& outputEquation_, const Grid& measurements );
00093 
00094 
00104         uint addOutput( const std::string& output, const std::string& diffs_output, const uint dim, const Grid& measurements );
00105 
00106 
00118         uint addOutput(         const std::string& output, const std::string& diffs_output, const uint dim,
00119                                                 const Grid& measurements, const std::string& colInd, const std::string& rowPtr  );
00120 
00121 
00126         BooleanType hasOutputs          () const;
00127 
00128 
00135         uint getDimOutput( uint index ) const;
00136 
00137 
00142          returnValue getNumSteps( DVector& _numSteps ) const;
00143 
00144 
00149          returnValue setNumSteps( const DVector& _numSteps );
00150 
00151 
00156      returnValue getOutputExpressions( std::vector<Expression>& outputExpressions_ ) const;
00157 
00158 
00163      returnValue getOutputGrids( std::vector<Grid>& outputGrids_ ) const;
00164 
00165 
00170      std::vector<DMatrix> getOutputDependencies( ) const;
00171 
00172 
00180      returnValue setModel( const DifferentialEquation& _f );
00181 
00182 
00190         returnValue setNARXmodel( const uint _delay, const DMatrix& _parms );
00191 
00192 
00199      returnValue setLinearInput( const DMatrix& M1_, const DMatrix& A1_, const DMatrix& B1_ );
00200 
00201 
00208      returnValue setLinearOutput( const DMatrix& M3_, const DMatrix& A3_, const OutputFcn& rhs_ );
00209 
00210 
00217      returnValue setLinearOutput(       const DMatrix& M3_, const DMatrix& A3_,
00218                                                                 const std::string& _rhs3,
00219                                                                 const std::string& _diffs3 );
00220 
00221 
00230      returnValue setModel(      const std::string& fileName,
00231                                                 const std::string& _rhs_ODE,
00232                                                 const std::string& _diffs_rhs_ODE );
00233 
00234 
00239      returnValue getIntegrationGrid( Grid& integrationGrid_ ) const;
00240 
00241 
00249      returnValue setIntegrationGrid(    const Grid& _ocpGrid,
00250                                                                         const uint _numSteps    );
00251 
00252 
00257      returnValue clearIntegrationGrid( );
00258 
00259 
00264      returnValue getModel( DifferentialEquation& _f ) const;
00265 
00266 
00271      returnValue getNARXmodel( uint& _delay, DMatrix& _parms ) const;
00272 
00273 
00280      returnValue getLinearInput( DMatrix& M1_, DMatrix& A1_, DMatrix& B1_ ) const;
00281 
00282 
00289      returnValue getLinearOutput( DMatrix& M3_, DMatrix& A3_, OutputFcn& rhs_ ) const;
00290 
00291 
00298      returnValue getLinearOutput( DMatrix& M3_, DMatrix& A3_ ) const;
00299 
00300 
00301      BooleanType hasEquidistantControlGrid              () const;
00302      BooleanType hasOutputFunctions             () const;
00303      BooleanType hasDifferentialEquation() const;
00304      BooleanType modelDimensionsSet() const;
00305      BooleanType exportRhs() const;
00306      BooleanType hasCompressedStorage() const;
00307 
00308 
00313      uint getNX( ) const;
00314      uint getNX1( ) const;
00315      uint getNX2( ) const;
00316      uint getNX3( ) const;
00317 
00318 
00323      uint getNDX( ) const;
00324      uint getNDX3( ) const;
00325 
00326 
00331      uint getNXA( ) const;
00332      uint getNXA3( ) const;
00333 
00338      uint getNU( ) const;
00339 
00344      uint getNP( ) const;
00345 
00350      uint getNOD( ) const;
00351 
00356      uint getN( ) const;
00357 
00364      returnValue setN( const uint N_ );
00365 
00366 
00371      DVector getDimOutputs( ) const;
00372 
00373 
00378      uint getNumOutputs( ) const;
00379 
00380 
00385      returnValue getDimOutputs( std::vector<uint>& dims ) const;
00386 
00387 
00392      DVector getNumMeas( ) const;
00393 
00394 
00395      const std::string getFileNameModel() const;
00396      const std::string getNameRhs() const;
00397      const std::string getNameDiffsRhs() const;
00398      const std::string getNameOutput() const;
00399      const std::string getNameDiffsOutput() const;
00400      returnValue getNameOutputs( std::vector<std::string>& names ) const;
00401      returnValue getNameDiffsOutputs( std::vector<std::string>& names ) const;
00402 
00403 
00404      //
00405     // PROTECTED FUNCTIONS:
00406     //
00407     protected:
00408 
00409 
00410     //
00411     // DATA MEMBERS:
00412     //
00413     protected:
00414 
00415      uint NX1;                                                                          
00416      uint NX2;                                                                          
00417      uint NX3;                                                                          
00418      uint NDX;                                                                          
00419      uint NDX3;                                                                         
00420      uint NXA;                                                                          
00421      uint NXA3;                                                                         
00422      uint NU;                                                                           
00423      uint NP;                                                                           
00424      uint NOD;                                                                          
00425      uint N;                                                                            
00427      BooleanType export_rhs;                                            
00428      BooleanType model_dimensions_set;                          
00429      std::string externModel;                                                   
00430      std::string rhs_name;                                                              
00431      std::string diffs_name;                                                            
00432      std::string rhs3_name;                                                             
00433      std::string diffs3_name;                                                   
00434      DifferentialEquation differentialEquation;         
00436      Grid integrationGrid;                                                      
00437      DVector numSteps;                                                          
00439      std::vector<Expression> outputExpressions;         
00440      std::vector<Grid> outputGrids;                                     
00441      std::vector<uint> dim_outputs;                                     
00442      std::vector<uint> num_meas;                                        
00443      std::vector<std::string> outputNames;                              
00444      std::vector<std::string> diffs_outputNames;                        
00445      std::vector<DVector> colInd_outputs;                       
00446      std::vector<DVector> rowPtr_outputs;                       
00448      // ------------------------------------
00449      // ------------------------------------
00450      //                 NEW VARIABLES IN VERSION 2.0:
00451      // ------------------------------------
00452      // ------------------------------------
00453      DMatrix M1;
00454      DMatrix A1;
00455      DMatrix B1;
00456 
00457      DMatrix M3;
00458      DMatrix A3;
00459      OutputFcn rhs3;
00460 
00461      // NARX model:
00462      uint delay;
00463      DMatrix parms;
00464 
00465 };
00466 
00467 
00468 CLOSE_NAMESPACE_ACADO
00469 
00470 
00471 
00472 #endif  // ACADO_TOOLKIT_MODELDATA_HPP
00473 
00474 /*
00475  *   end of file
00476  */


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