integrator_export.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 
00027 
00035 #ifndef ACADO_TOOLKIT_INTEGRATOR_EXPORT_HPP
00036 #define ACADO_TOOLKIT_INTEGRATOR_EXPORT_HPP
00037 
00038 #include <acado/matrix_vector/matrix_vector.hpp>
00039 #include <acado/code_generation/export_algorithm_factory.hpp>
00040 #include <acado/ocp/model_data.hpp>
00041 #include <acado/code_generation/integrators/integrator_export_types.hpp>
00042 
00043 
00044 BEGIN_NAMESPACE_ACADO
00045 
00046 
00057 class IntegratorExport : public ExportAlgorithm
00058 {
00059     //
00060     // PUBLIC MEMBER FUNCTIONS:
00061     //
00062 
00063     public:
00064 
00070         IntegratorExport(       UserInteraction* _userInteraction = 0,
00071                                                         const std::string& _commonHeaderName = ""
00072                                                         );
00073 
00078         IntegratorExport(       const IntegratorExport& arg
00079                                                         );
00080 
00083         virtual ~IntegratorExport( );
00084 
00089                 IntegratorExport& operator=(    const IntegratorExport& arg
00090                                                                                 );
00091 
00092 
00097                 virtual returnValue setup( ) = 0;
00098 
00099 
00107                 virtual returnValue setDifferentialEquation( const Expression& rhs ) = 0;
00108 
00109 
00116                 virtual returnValue setLinearInput( const DMatrix& M1, const DMatrix& A1, const DMatrix& B1 );
00117 
00118 
00125                 virtual returnValue setLinearOutput( const DMatrix& M3, const DMatrix& A3, const Expression& rhs );
00126 
00127 
00134                 virtual returnValue setLinearOutput( const DMatrix& M3, const DMatrix& A3, const std::string& _rhs3, const std::string& _diffs_rhs3 );
00135 
00136 
00145                 virtual returnValue setModel(   const std::string& _name_ODE,
00146                                                                                 const std::string& _name_diffs_ODE );
00147 
00148 
00157                 virtual returnValue setNARXmodel( const uint delay, const DMatrix& parms ) = 0;
00158 
00159 
00166                 virtual returnValue setModelData(       const ModelData& data  );
00167 
00168 
00175                 virtual returnValue updateInputSystem(  ExportStatementBlock* block,
00176                                                                                                 const ExportIndex& index1,
00177                                                                                                 const ExportIndex& index2,
00178                                                                                                 const ExportIndex& tmp_index    );
00179 
00180 
00187                 virtual returnValue propagateInputSystem(       ExportStatementBlock* block,
00188                                                                                                         const ExportIndex& index1,
00189                                                                                                         const ExportIndex& index2,
00190                                                                                                         const ExportIndex& index3,
00191                                                                                                         const ExportIndex& tmp_index    );
00192 
00193 
00200                 virtual returnValue updateImplicitSystem(       ExportStatementBlock* block,
00201                                                                                                         const ExportIndex& index1,
00202                                                                                                         const ExportIndex& index2,
00203                                                                                                         const ExportIndex& tmp_index    );
00204 
00205 
00212                 virtual returnValue propagateImplicitSystem(    ExportStatementBlock* block,
00213                                                                                                                 const ExportIndex& index1,
00214                                                                                                                 const ExportIndex& index2,
00215                                                                                                                 const ExportIndex& index3,
00216                                                                                                                 const ExportIndex& tmp_index    );
00217 
00218 
00225                 virtual returnValue updateOutputSystem(         ExportStatementBlock* block,
00226                                                                                                         const ExportIndex& index1,
00227                                                                                                         const ExportIndex& index2,
00228                                                                                                         const ExportIndex& tmp_index    );
00229 
00230 
00237                 virtual returnValue propagateOutputSystem(      ExportStatementBlock* block,
00238                                                                                                         const ExportIndex& index1,
00239                                                                                                         const ExportIndex& index2,
00240                                                                                                         const ExportIndex& index3,
00241                                                                                                         const ExportIndex& tmp_index    );
00242 
00243 
00250                 virtual returnValue setGrid(    const Grid& _grid   );
00251 
00252 
00259                 virtual returnValue getDataDeclarations(        ExportStatementBlock& declarations,
00260                                                                                                         ExportStruct dataStruct = ACADO_ANY
00261                                                                                                         ) const = 0;
00262 
00263 
00270                 virtual returnValue getFunctionDeclarations(    ExportStatementBlock& declarations
00271                                                                                                                 ) const = 0;
00272 
00273 
00274 
00281                 virtual returnValue getCode(    ExportStatementBlock& code
00282                                                                                 ) = 0;
00283                                                         
00284         
00292                 virtual returnValue setupOutput( const std::vector<Grid> outputGrids_,
00293                                                                           const std::vector<Expression> rhs ) = 0;
00294 
00295 
00305                 virtual returnValue setupOutput(  const std::vector<Grid> outputGrids_,
00306                                                                                   const std::vector<std::string> _outputNames,
00307                                                                                   const std::vector<std::string> _diffs_outputNames,
00308                                                                                   const std::vector<uint> _dims_output ) = 0;
00309 
00310 
00321                 virtual returnValue setupOutput(  const std::vector<Grid> outputGrids_,
00322                                                                                   const std::vector<std::string> _outputNames,
00323                                                                                   const std::vector<std::string> _diffs_outputNames,
00324                                                                                   const std::vector<uint> _dims_output,
00325                                                                                   const std::vector<DMatrix> _outputDependencies ) = 0;
00326 
00327 
00332                 virtual returnValue getGrid( Grid& grid_ ) const;
00333 
00334 
00339                 virtual returnValue getNumSteps( DVector& _numSteps ) const;
00340                 
00341                 
00346                 virtual returnValue getOutputExpressions( std::vector<Expression>& outputExpressions_ ) const;
00347 
00348 
00353                 virtual returnValue getOutputGrids( std::vector<Grid>& outputGrids_ ) const;
00354 
00355 
00360                 virtual bool equidistantControlGrid( ) const;
00361 
00362 
00363                 const std::string getNameRHS() const;
00364                 const std::string getNameDiffsRHS() const;
00365                 virtual const std::string getNameFullRHS() const;
00366 
00367                 const std::string getNameOutputRHS() const;
00368                 const std::string getNameOutputDiffs() const;
00369 
00370                 const std::string getNameOUTPUT( uint index ) const;
00371                 const std::string getNameDiffsOUTPUT( uint index ) const;
00372                 uint getDimOUTPUT( uint index ) const;
00373 
00374 
00375 
00376         protected:
00377 
00378 
00385                 DMatrix expandOutputMatrix( const DMatrix& A3 );
00386 
00387 
00394                 virtual returnValue copy(       const IntegratorExport& arg
00395                                                         );
00396 
00397 
00402                 virtual returnValue clear( );
00403 
00404 
00411                 uint getIntegrationInterval( double time );
00412 
00413 
00418                 virtual ExportVariable getAuxVariable() const = 0;
00419 
00420 
00421     protected:
00422 
00423                 uint NX1;
00424                 uint NX2;
00425                 uint NX3;
00426                 uint NDX3;
00427                 uint NXA3;
00428 
00429                 uint diffsDim;                                                  
00430                 uint inputDim;                                                  
00432                 bool timeDependant;
00433 
00434                 DMatrix M11, A11, B11;
00435                 DMatrix A33, M33;
00436 
00437         bool exportRhs;                                         
00438         bool crsFormat;                                         
00440                 Grid grid;                                                      
00441                 DVector numSteps;                                       
00443                 ExportFunction fullRhs;                         
00444                 ExportVariable  rhs_in;
00445                 ExportVariable  rhs_out;
00446                 
00447                 ExportFunction integrate;                       
00448                 ExportAcadoFunction rhs;                        
00449                 ExportAcadoFunction diffs_rhs;          
00451                 ExportAcadoFunction lin_input;
00452 
00453                 ExportAcadoFunction rhs3;
00454                 ExportAcadoFunction diffs_rhs3;
00455 
00456                 ExportVariable  error_code;                     
00457                 ExportVariable  reset_int;                      
00458                 ExportVariable  rk_index;                       
00459                 ExportVariable  rk_ttt;                         
00460                 ExportVariable  rk_xxx;                         
00461                 ExportVariable  rk_eta;                         
00463                 ExportVariable  rk_diffsPrev1;
00464                 ExportVariable  rk_diffsNew1;
00465                 
00466                 ExportVariable  rk_diffsPrev2;                  
00467                 ExportVariable  rk_diffsNew2;                   
00468                 ExportVariable  rk_diffsTemp2;                  
00470                 ExportVariable  rk_diffsNew3;
00471                 ExportVariable  rk_diffsPrev3;
00472 
00473                 DifferentialState                       x;              
00474                 DifferentialStateDerivative dx;         
00475                 AlgebraicState                          z;              
00476                 Control                                 u;              
00477                 OnlineData                              od;             
00479         std::vector<Grid> outputGrids;                                          
00480         std::vector<Expression> outputExpressions;                      
00481         std::vector<DMatrix> outputDependencies;                        
00482         std::vector<ExportAcadoFunction> outputs;                       
00483         std::vector<ExportAcadoFunction> diffs_outputs;         
00485         std::vector<uint> num_outputs;                                  
00486 };
00487 
00489 typedef ExportAlgorithmFactory<IntegratorExport, ExportIntegratorType> IntegratorExportFactory;
00490 
00492 typedef std::tr1::shared_ptr< IntegratorExport > IntegratorExportPtr;
00493 
00494 CLOSE_NAMESPACE_ACADO
00495 
00496 
00497 #endif  // ACADO_TOOLKIT_INTEGRATOR_EXPORT_HPP
00498 
00499 // end of file.


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