variables_grid.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_VARIABLES_GRID_HPP
00034 #define ACADO_TOOLKIT_VARIABLES_GRID_HPP
00035 
00036 #include <acado/variables_grid/matrix_variables_grid.hpp>
00037 
00038 
00039 BEGIN_NAMESPACE_ACADO
00040 
00041 
00056 class VariablesGrid : public MatrixVariablesGrid
00057 {
00058         friend class OptimizationAlgorithmBase;
00059         friend class OptimizationAlgorithm;
00060         friend class RealTimeAlgorithm;
00061 
00062     //
00063     // PUBLIC MEMBER FUNCTIONS:
00064     //
00065     public:
00066 
00069         VariablesGrid( );
00070 
00085         VariablesGrid(  uint _dim,
00086                                                 const Grid& _grid,
00087                                                 VariableType _type = VT_UNKNOWN,
00088                                                 const char** const _names = 0,
00089                                                 const char** const _units = 0,
00090                                                 const DVector* const _scaling = 0,
00091                                                 const DVector* const _lb = 0,
00092                                                 const DVector* const _ub = 0,
00093                                                 const BooleanType* const _autoInit = 0
00094                                                 );
00095 
00096 
00111         VariablesGrid(  uint _dim,
00112                                                 uint _nPoints,
00113                                                 VariableType _type = VT_UNKNOWN,
00114                                                 const char** const _names = 0,
00115                                                 const char** const _units = 0,
00116                                                 const DVector* const _scaling = 0,
00117                                                 const DVector* const _lb = 0,
00118                                                 const DVector* const _ub = 0,
00119                                                 const BooleanType* const _autoInit = 0
00120                                                 );
00121 
00140         VariablesGrid(  uint _dim,
00141                                                 double _firstTime,
00142                                                 double _lastTime,
00143                                                 uint _nPoints,
00144                                                 VariableType _type = VT_UNKNOWN,
00145                                                 const char** const _names = 0,
00146                                                 const char** const _units = 0,
00147                                                 const DVector* const _scaling = 0,
00148                                                 const DVector* const _lb = 0,
00149                                                 const DVector* const _ub = 0,
00150                                                 const BooleanType* const _autoInit = 0
00151                                                 );
00152 
00161         VariablesGrid(  const DVector& arg,
00162                                                 const Grid& _grid = trivialGrid,
00163                                                 VariableType _type = VT_UNKNOWN
00164                                                 );
00165 
00179         VariablesGrid(  const DMatrix& arg,
00180                                                 VariableType _type = VT_UNKNOWN
00181                                                 );
00182 
00187         VariablesGrid(  const VariablesGrid& rhs
00188                                                 );
00189 
00194         VariablesGrid(  const MatrixVariablesGrid& rhs
00195                                                 );
00196 
00197 
00200         ~VariablesGrid( );
00201 
00202 
00207         VariablesGrid& operator=(       const VariablesGrid& rhs
00208                                                                         );
00209 
00214         VariablesGrid& operator=(       const MatrixVariablesGrid& rhs
00215                                                                         );
00216 
00217         operator DMatrix() const;
00218 
00230         VariablesGrid& operator=(       const DMatrix& rhs
00231                                                                         );
00232 
00233 
00241         inline BooleanType operator==(  const VariablesGrid& arg
00242                                                                         ) const;
00243 
00251         inline double& operator()(      uint pointIdx,
00252                                                                         uint rowIdx
00253                                                                         );
00254 
00262         inline double operator()(       uint pointIdx,
00263                                                                         uint rowIdx
00264                                                                         ) const;
00265 
00266 
00273         VariablesGrid operator()(       const uint rowIdx
00274                                                                         ) const;
00275 
00283         VariablesGrid operator[](       const uint pointIdx
00284                                                                         ) const;
00285 
00286 
00293                 inline VariablesGrid operator+( const VariablesGrid& arg
00294                                                                                 ) const;
00295 
00302                 inline VariablesGrid& operator+=(       const VariablesGrid& arg
00303                                                                                         );
00304 
00305 
00313                 inline VariablesGrid operator-( const VariablesGrid& arg
00314                                                                                 ) const;
00315 
00322                 inline VariablesGrid& operator-=(       const VariablesGrid& arg
00323                                                                                         );
00324 
00325 
00330         returnValue init( );
00331 
00347                 returnValue     init(   uint _dim,
00348                                                         const Grid& _grid,
00349                                                         VariableType _type = VT_UNKNOWN,
00350                                                         const char** const _names = 0,
00351                                                         const char** const _units = 0,
00352                                                         const DVector* const _scaling = 0,
00353                                                         const DVector* const _lb = 0,
00354                                                         const DVector* const _ub = 0,
00355                                                         const BooleanType* const _autoInit = 0
00356                                                         );
00357 
00374         returnValue init(       uint _dim,
00375                                                         uint _nPoints,
00376                                                         VariableType _type = VT_UNKNOWN,
00377                                                         const char** const _names = 0,
00378                                                         const char** const _units = 0,
00379                                                         const DVector* const _scaling = 0,
00380                                                         const DVector* const _lb = 0,
00381                                                         const DVector* const _ub = 0,
00382                                                         const BooleanType* const _autoInit = 0
00383                                                         );
00384 
00405         returnValue init(       uint _dim,
00406                                                         double _firstTime,
00407                                                         double _lastTime,
00408                                                         uint _nPoints,
00409                                                         VariableType _type = VT_UNKNOWN,
00410                                                         const char** const _names = 0,
00411                                                         const char** const _units = 0,
00412                                                         const DVector* const _scaling = 0,
00413                                                         const DVector* const _lb = 0,
00414                                                         const DVector* const _ub = 0,
00415                                                         const BooleanType* const _autoInit = 0
00416                                                         );
00417 
00427         returnValue init(       const DVector& arg,
00428                                                         const Grid& _grid = trivialGrid,
00429                                                         VariableType _type = VT_UNKNOWN
00430                                                         );
00431 
00432 
00441                 returnValue addVector(  const DVector& newVector,
00442                                                                 double newTime = -INFTY
00443                                                                 );
00444 
00445 
00455                 returnValue setVector(  uint pointIdx,                  
00456                                                                 const DVector& _values  
00457                                                                 );
00458 
00467                 returnValue setAllVectors(      const DVector& _values
00468                                                                         );
00469 
00470 
00477                 DVector getVector(      uint pointIdx
00478                                                         ) const;
00479 
00484                 DVector getFirstVector( ) const;
00485 
00490                 DVector getLastVector( ) const;
00491 
00492 
00502                 returnValue appendTimes(        const VariablesGrid& arg,
00503                                                                         MergeMethod _mergeMethod = MM_DUPLICATE
00504                                                                         );
00505 
00515                 returnValue appendTimes(        const DMatrix& arg,
00516                                                                         MergeMethod _mergeMethod = MM_DUPLICATE
00517                                                                         );
00518                                                                         
00527                 returnValue appendValues(       const VariablesGrid& arg
00528                                                                         );
00529 
00530 
00544                 returnValue merge(      const VariablesGrid& arg,
00545                                                         MergeMethod _mergeMethod = MM_DUPLICATE,
00546                                                         BooleanType keepOverlap = BT_TRUE
00547                                                         );
00548 
00549 
00558         VariablesGrid getTimeSubGrid(   uint startIdx,
00559                                                                                 uint endIdx
00560                                                                                 ) const;
00561 
00570                 VariablesGrid getTimeSubGrid(   double startTime,
00571                                                                                 double endTime
00572                                                                                 ) const;
00573 
00586         VariablesGrid getValuesSubGrid( uint startIdx,
00587                                                                                 uint endIdx
00588                                                                                 ) const;
00589 
00590 
00597         VariablesGrid& shiftTimes(      double timeShift
00598                                                                         );
00599 
00606                 VariablesGrid& shiftBackwards( DVector lastValue = emptyVector );
00607 
00608 
00615                 returnValue getSum(     DVector& sum
00616                                                         ) const;
00617 
00625                 returnValue getIntegral(        InterpolationMode mode,
00626                                                                         DVector& value
00627                                                                         ) const;
00628 
00629     //
00630     // PROTECTED MEMBER FUNCTIONS:
00631     //
00632     protected:
00633 
00642         returnValue initializeFromBounds( );
00643 };
00644 
00645 CLOSE_NAMESPACE_ACADO
00646 
00647 #include <acado/variables_grid/variables_grid.ipp>
00648 
00649 BEGIN_NAMESPACE_ACADO
00650 
00651 static       VariablesGrid emptyVariablesGrid;
00652 static const VariablesGrid emptyConstVariablesGrid;
00653 
00654 CLOSE_NAMESPACE_ACADO
00655 
00656 #endif  // ACADO_TOOLKIT_VARIABLES_GRID_HPP
00657 
00658 /*
00659  *      end of file
00660  */


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Thu Aug 27 2015 12:01:31