powerkite.cpp
Go to the documentation of this file.
00001 
00002 #include <acado_code_generation.hpp>
00003 
00004 USING_NAMESPACE_ACADO
00005 
00006 int main( ){
00007         
00008         // DIFFERENTIAL STATES :
00009 // -------------------------
00010    DifferentialState      r;      //  the length r of the cable
00011    DifferentialState    phi;      //  the angle phi
00012    DifferentialState  theta;      //  the angle theta
00013 // -------------------------      //  -------------------------------------------
00014    DifferentialState     dr;      //  first  derivative of r0    with respect to t
00015    DifferentialState   dphi;      //  first  derivative of phi   with respect to t
00016    DifferentialState dtheta;      //  first  derivative of theta with respect to t
00017 // -------------------------      //  -------------------------------------------
00018    DifferentialState      n;      //  winding number
00019 // -------------------------      //  -------------------------------------------
00020    DifferentialState    Psi;      //  the roll angle Psi
00021    DifferentialState     CL;      //  the aerodynamic lift coefficient
00022 // -------------------------      //  -------------------------------------------
00023    DifferentialState      W;      //  integral over the power at the generator
00024                                   //  ( = ENERGY )
00025 
00026 
00027 // CONTROL :
00028 // -------------------------
00029    Control             ddr0;      //  second derivative of r0    with respect to t
00030    Control             dPsi;      //  first  derivative of Psi   with respect to t
00031    Control              dCL;      //  first  derivative of CL    with respect to t
00032 
00033 
00034 // PARAMETERS :
00035 // ------------------------
00036                                      //  PARAMETERS OF THE KITE :
00037                                      //  -----------------------------
00038    double         mk =  850.00;      //  mass of the kite               //  [ kg    ]
00039    double          A =  500.00;      //  effective area                 //  [ m^2   ]
00040    double          V =  720.00;      //  volume                         //  [ m^3   ]
00041    double        cd0 =    0.04;      //  aerodynamic drag coefficient   //  [       ]
00042                                      //  ( cd0: without downwash )
00043    double          K =    0.04;      //  induced drag constant          //  [       ]
00044 
00045 
00046                                      //   PHYSICAL CONSTANTS :
00047                                      //  -----------------------------
00048    double          g =    9.81;      //  gravitational constant         //  [ m /s^2]
00049    double        rho =    1.23;      //  density of the air             //  [ kg/m^3]
00050 
00051                                      //  PARAMETERS OF THE CABLE :
00052                                      //  -----------------------------
00053    double       rhoc = 1450.00;      //  density of the cable           //  [ kg/m^3]
00054    double         cc =    1.00;      //  frictional constant            //  [       ]
00055    double         dc = 0.05614;      //  diameter                       //  [ m     ]
00056 
00057 
00058                                      //  PARAMETERS OF THE WIND :
00059                                      //  -----------------------------
00060    double         w0 =   10.00;      //  wind velocity at altitude h0   //  [ m/s   ]
00061    double         h0 =  100.00;      //  the altitude h0                //  [ m     ]
00062    double         hr =    0.10;      //  roughness length               //  [ m     ]
00063 
00064 
00065 
00066 // OTHER VARIABLES :
00067 // ------------------------
00068 
00069    double AQ               ;      //  cross sectional area
00070 
00071    IntermediateState     mc;      //  mass of the cable
00072    IntermediateState     m ;      //  effective inertial mass
00073    IntermediateState     m_;      //  effective gravitational mass
00074 
00075    IntermediateState     Cg;
00076 
00077    IntermediateState     dm;      //  first  derivative of m     with respect to t
00078 
00079 
00080 // DEFINITION OF PI :
00081 // ------------------------
00082 
00083    double PI = 3.1415926535897932;
00084 
00085 
00086 // ORIENTATION AND FORCES :
00087 // ------------------------
00088 
00089    IntermediateState h               ;      //  altitude of the kite
00090    IntermediateState w               ;      //  the wind at altitude h
00091    IntermediateState we          [ 3];      //  effective wind vector
00092    IntermediateState nwe             ;      //  norm of the effective wind vector
00093    IntermediateState nwep            ;      //  -
00094    IntermediateState ewep        [ 3];      //  projection of ewe
00095    IntermediateState eta            ;      //  angle eta: cf. [2]
00096    IntermediateState et          [ 3];      //  unit vector from the left to the right wing tip
00097    IntermediateState Caer            ;
00098    IntermediateState Cf              ;      //  simple constants
00099    IntermediateState CD              ;      //  the aerodynamic drag coefficient
00100    IntermediateState Fg          [ 3];      //  the gravitational force
00101    IntermediateState Faer        [ 3];      //  the aerodynamic force
00102    IntermediateState Ff          [ 3];      //  the frictional force
00103    IntermediateState F           [ 3];      //  the total force
00104 
00105 
00106 // TERMS ON RIGHT-HAND-SIDE
00107 // OF THE DIFFERENTIAL
00108 // EQUATIONS              :
00109 // ------------------------
00110 
00111    IntermediateState a_pseudo    [ 3];      //  the pseudo accelaration
00112    IntermediateState dn              ;      //  the time derivate of the kite's winding number
00113    IntermediateState ddr             ;      //  second derivative of s     with respect to t
00114    IntermediateState ddphi           ;      //  second derivative of phi   with respect to t
00115    IntermediateState ddtheta         ;      //  second derivative of theta with respect to t
00116    IntermediateState power           ;      //  the power at the generator
00117 // ------------------------                 //  ----------------------------------------------
00118    IntermediateState regularisation  ;      //  regularisation of controls
00119 
00120 
00121 
00122 //                        MODEL EQUATIONS :
00123 // ===============================================================
00124 
00125 
00126 
00127 // CROSS AREA OF THE CABLE :
00128 // ---------------------------------------------------------------
00129 
00130    AQ      =  PI*dc*dc/4.0                                       ;
00131 
00132 // THE EFECTIVE MASS' :
00133 // ---------------------------------------------------------------
00134 
00135    mc      =  rhoc*AQ*r        ;   // mass of the cable
00136    m       =  mk + mc     / 3.0;   // effective inertial mass
00137    m_      =  mk + mc     / 2.0;   // effective gravitational mass
00138 // -----------------------------   // ----------------------------
00139    dm      =  (rhoc*AQ/ 3.0)*dr;   // time derivative of the mass
00140 
00141 
00142 // WIND SHEAR MODEL :
00143 // ---------------------------------------------------------------
00144 
00145    h       =  r*cos(theta)                                       ;
00146    w       =  log(h/hr) / log(h0/hr) *w0                         ;
00147 
00148 
00149 // EFFECTIVE WIND IN THE KITE`S SYSTEM :
00150 // ---------------------------------------------------------------
00151 
00152    we[0]   =  w*sin(theta)*cos(phi) -              dr    ;
00153    we[1]   = -w*sin(phi)            - r*sin(theta)*dphi  ;
00154    we[2]   = -w*cos(theta)*cos(phi) + r           *dtheta;
00155 
00156 
00157 // CALCULATION OF THE KITE`S TRANSVERSAL AXIS :
00158 // ---------------------------------------------------------------
00159 
00160    nwep    =  pow(                we[1]*we[1] + we[2]*we[2], 0.5 );
00161    nwe     =  pow(  we[0]*we[0] + we[1]*we[1] + we[2]*we[2], 0.5 );
00162    eta     =  asin( we[0]*tan(Psi)/ nwep )                       ;
00163 
00164 // ---------------------------------------------------------------
00165 
00166 // ewep[0] =  0.0                                                ;
00167    ewep[1] =  we[1] / nwep                                       ;
00168    ewep[2] =  we[2] / nwep                                       ;
00169 
00170 // ---------------------------------------------------------------
00171 
00172    et  [0] =  sin(Psi)                                                  ;
00173    et  [1] =  (-cos(Psi)*sin(eta))*ewep[1] - (cos(Psi)*cos(eta))*ewep[2];
00174    et  [2] =  (-cos(Psi)*sin(eta))*ewep[2] + (cos(Psi)*cos(eta))*ewep[1];
00175 
00176 
00177 
00178 
00179 // CONSTANTS FOR SEVERAL FORCES :
00180 // ---------------------------------------------------------------
00181 
00182    Cg      =  (V*rho-m_)*g                                       ;
00183    Caer    =  (rho*A/2.0 )*nwe                                   ;
00184    Cf      =  (rho*dc/8.0)*r*nwe                                 ;
00185 
00186 
00187 // THE DRAG-COEFFICIENT :
00188 // ---------------------------------------------------------------
00189 
00190    CD      =  cd0 + K*CL*CL                                      ;
00191 
00192 
00193 
00194 // SUM OF GRAVITATIONAL AND LIFTING FORCE :
00195 // ---------------------------------------------------------------
00196 
00197    Fg  [0] =  Cg  *  cos(theta)                                  ;
00198 // Fg  [1] =  Cg  *  0.0                                         ;
00199    Fg  [2] =  Cg  *  sin(theta)                                  ;
00200 
00201 
00202 // SUM OF THE AERODYNAMIC FORCES :
00203 // ---------------------------------------------------------------
00204 
00205    Faer[0] =  Caer*( CL*(we[1]*et[2]-we[2]*et[1]) + CD*we[0] )   ;
00206    Faer[1] =  Caer*( CL*(we[2]*et[0]-we[0]*et[2]) + CD*we[1] )   ;
00207    Faer[2] =  Caer*( CL*(we[0]*et[1]-we[1]*et[0]) + CD*we[2] )   ;
00208 
00209 
00210 // THE FRICTION OF THE CABLE :
00211 // ---------------------------------------------------------------
00212 
00213 // Ff  [0] =  Cf  *  cc* we[0]                                   ;
00214    Ff  [1] =  Cf  *  cc* we[1]                                   ;
00215    Ff  [2] =  Cf  *  cc* we[2]                                   ;
00216 
00217 
00218 
00219 // THE TOTAL FORCE :
00220 // ---------------------------------------------------------------
00221 
00222    F   [0] = Fg[0] + Faer[0]                                     ;
00223    F   [1] =         Faer[1] + Ff[1]                             ;
00224    F   [2] = Fg[2] + Faer[2] + Ff[2]                             ;
00225 
00226 
00227 
00228 // THE PSEUDO ACCELERATION:
00229 // ---------------------------------------------------------------
00230 
00231    a_pseudo [0] =  - ddr0
00232                    + r*(                         dtheta*dtheta
00233                          + sin(theta)*sin(theta)*dphi  *dphi   )
00234                    - dm/m*dr                                     ;
00235 
00236    a_pseudo [1] =  - 2.0*cos(theta)/sin(theta)*dphi*dtheta
00237                    - 2.0*dr/r*dphi
00238                    - dm/m*dphi                                   ;
00239 
00240    a_pseudo [2] =    cos(theta)*sin(theta)*dphi*dphi
00241                    - 2.0*dr/r*dtheta
00242                    - dm/m*dtheta                                 ;
00243 
00244 
00245 
00246 
00247 // THE EQUATIONS OF MOTION:
00248 // ---------------------------------------------------------------
00249 
00250    ddr          =  F[0]/m                + a_pseudo[0]           ;
00251    ddphi        =  F[1]/(m*r*sin(theta)) + a_pseudo[1]           ;
00252    ddtheta      = -F[2]/(m*r           ) + a_pseudo[2]           ;
00253 
00254 
00255 
00256 
00257 
00258 // THE DERIVATIVE OF THE WINDING NUMBER :
00259 // ---------------------------------------------------------------
00260 
00261    dn           =  (        dphi*ddtheta - dtheta*ddphi     ) /
00262                    (2.0*PI*(dphi*dphi    + dtheta*dtheta)   )      ;
00263 
00264 
00265 
00266 // THE POWER AT THE GENERATOR :
00267 // ---------------------------------------------------------------
00268 
00269    power        =   m*ddr*dr                                     ;
00270 
00271 
00272 
00273 // REGULARISATION TERMS :
00274 // ---------------------------------------------------------------
00275 
00276 
00277    regularisation =    5.0e2 * ddr0    * ddr0
00278                      + 1.0e8 * dPsi    * dPsi
00279                      + 1.0e5 * dCL     * dCL
00280                      + 2.5e5 * dn      * dn
00281                      + 2.5e7 * ddphi   * ddphi;
00282                      + 2.5e7 * ddtheta * ddtheta;
00283                      + 2.5e6 * dtheta  * dtheta;
00284 //                   ---------------------------
00285 
00286 
00287 
00288 // THE "RIGHT-HAND-SIDE" OF THE ODE:
00289 // ---------------------------------------------------------------
00290    DifferentialEquation f;
00291 
00292    f  << dot(r)      ==  dr                             ;
00293    f  << dot(phi)    ==  dphi                           ;
00294    f  << dot(theta)  ==  dtheta                         ;
00295    f  << dot(dr)     ==  ddr0                           ;
00296    f  << dot(dphi)   ==  ddphi                          ;
00297    f  << dot(dtheta) ==  ddtheta                        ;
00298    f  << dot(n)      ==  dn                             ;
00299    f  << dot(Psi)    ==  dPsi                           ;
00300    f  << dot(CL)     ==  dCL                            ;
00301    f  << dot(W)      == (-power + regularisation)*1.0e-6;
00302 
00303         // DEFINE THE WEIGHTING MATRICES:
00304         // ----------------------------------------------------------
00305         Expression states;
00306         states << r;
00307         states << phi;
00308         states << theta;
00309         states << dr;
00310         states << dphi;
00311         states << dtheta;
00312         states << n;
00313         states << Psi;
00314         states << CL;
00315         states << W;
00316         
00317         Expression controls;
00318         controls << ddr0;
00319         controls << dPsi;
00320         controls << dCL;
00321         
00322         Function rf, rfN;
00323         rf << states;
00324         rf << controls;
00325         
00326         rfN << states;
00327         
00328         BMatrix Wmat(rf.getDim(), rf.getDim()); Wmat.setAll( true );
00329         BMatrix WNmat(rfN.getDim(), rfN.getDim()); WNmat.setAll( true );
00330         // ----------------------------------------------------------
00331 
00332 
00333         // SET UP THE MPC - OPTIMAL CONTROL PROBLEM:
00334         // ----------------------------------------------------------
00335 
00336     const double t_start =  0.0;
00337     const double t_end   = 18.0;
00338     const uint N                  = 18;
00339     
00340         OCP ocp( t_start, t_end, N );
00341     ocp.minimizeMayerTerm( W );
00342         
00343         ocp.setModel( f );
00344 
00345     ocp.subjectTo( -0.34   <= phi   <= 0.34   );
00346     ocp.subjectTo(  0.85   <= theta <= 1.45   );
00347     ocp.subjectTo( -40.0   <= dr    <= 10.0   );
00348     ocp.subjectTo( -0.7    <= n     <= 0.90   );
00349     ocp.subjectTo( -0.29   <= Psi   <= 0.29   );
00350     ocp.subjectTo(  0.1    <= CL    <= 1.50   );
00351     
00352     ocp.subjectTo( -25.0   <= ddr0  <= 25.0   );
00353     ocp.subjectTo( -0.065  <= dPsi  <= 0.065  );
00354     ocp.subjectTo( -3.5    <= dCL   <= 3.5    );
00355         
00356         ocp.subjectTo( AT_END, 0 <= r <= 0 );
00357         ocp.subjectTo( AT_END, 0 <= phi <= 0 );
00358         ocp.subjectTo( AT_END, 0 <= theta <= 0 );
00359         ocp.subjectTo( AT_END, 0 <= dr <= 0 );
00360         ocp.subjectTo( AT_END, 0 <= dphi <= 0 );
00361         ocp.subjectTo( AT_END, 0 <= dtheta <= 0 );
00362         ocp.subjectTo( AT_END, -0.7 <= n <= 0.90 );
00363     ocp.subjectTo( AT_END, 0 <= Psi <= 0 );
00364     ocp.subjectTo( AT_END, 0 <= CL <= 0 );
00365         ocp.subjectTo( AT_END, 0 <= W <= 1e6 );
00366 
00367         // ----------------------------------------------------------
00368 
00369         // DEFINE AN MPC EXPORT MODULE AND GENERATE THE CODE:
00370         // ----------------------------------------------------------
00371         OCPexport mpc( ocp );
00372 
00373         mpc.set( HESSIAN_APPROXIMATION,       EXACT_HESSIAN             );
00374         mpc.set( DISCRETIZATION_TYPE,         MULTIPLE_SHOOTING         );
00375         mpc.set( INTEGRATOR_TYPE,             INT_RK4                           );
00376         mpc.set( NUM_INTEGRATOR_STEPS,        18                        );
00377         mpc.set( QP_SOLVER,                   QP_QPOASES                );
00378         mpc.set( HOTSTART_QP,                 NO                        );
00379         mpc.set( GENERATE_TEST_FILE,          NO                        );
00380         mpc.set( GENERATE_MAKE_FILE,          NO                        );
00381         mpc.set( GENERATE_MATLAB_INTERFACE,   YES                       );
00382         mpc.set( SPARSE_QP_SOLUTION,              FULL_CONDENSING_N2    );
00383         mpc.set( DYNAMIC_SENSITIVITY,             THREE_SWEEPS                  );
00384         mpc.set( CG_HARDCODE_CONSTRAINT_VALUES, NO                                      );
00385         mpc.set( CG_USE_VARIABLE_WEIGHTING_MATRIX, YES                          );
00386 
00387         mpc.exportCode( "mpc_export" );
00388         mpc.printDimensionsQP( );
00389         // ----------------------------------------------------------
00390 
00391 
00392         // DEFINE A SIM EXPORT MODULE AND GENERATE THE CODE:
00393         // ----------------------------------------------------------
00394         SIMexport sim( 1, t_end/(5*N) );
00395         
00396         sim.setModel( f );
00397         
00398         sim.set( INTEGRATOR_TYPE,                               INT_RK4         );
00399         sim.set( NUM_INTEGRATOR_STEPS,                  2                       );
00400         sim.set( DYNAMIC_SENSITIVITY,           NO_SENSITIVITY  );
00401         sim.set( GENERATE_MATLAB_INTERFACE,     YES         );
00402         sim.exportCode( "sim_export" );
00403         // ----------------------------------------------------------
00404 
00405     return 0;
00406 }
00407 
00408 
00409 


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