diff --git a/.gitignore b/.gitignore index 5195983e3..72d12a0ca 100644 --- a/.gitignore +++ b/.gitignore @@ -14,6 +14,7 @@ _build # MATLAB files *.m~ +*slprj* # ide settings and files .idea diff --git a/DRC_Fortran/Source/ControllerBlocks.f90 b/DRC_Fortran/Source/ControllerBlocks.f90 index 1b7861cfc..fee3d326f 100644 --- a/DRC_Fortran/Source/ControllerBlocks.f90 +++ b/DRC_Fortran/Source/ControllerBlocks.f90 @@ -148,7 +148,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData) ! Extended Kalman Filter (EKF) implementation ELSEIF (CntrPar%WE_Mode == 2) THEN ! Define contant values - L = 2.0 * CntrPar%WE_BladeRadius + L = 4.0 * CntrPar%WE_BladeRadius Ti = 0.2 R_m = 0.02 H = RESHAPE((/1.0 , 0.0 , 0.0/),(/1,3/)) @@ -185,10 +185,10 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData) F(2,3) = PI * v_t/(2.0*L) ! Update process noise covariance - Q(1,1) = 0.0001 + Q(1,1) = 0.00001 Q(2,2) =(PI * (v_m**3.0) * (Ti**2.0)) / L Q(3,3) = (2.0**2.0)/600.0 -\ + ! Prediction update ! Tau_r = 0.5 * CntrPar%WE_RhoAir * PI *CntrPar%WE_BladeRadius**3 * Cp_op * v_h**2 * 1.0/(lambda) Tau_r = AeroDynTorque(LocalVar,CntrPar,PerfData) @@ -215,6 +215,7 @@ SUBROUTINE WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData) v_h = v_t + v_m LocalVar%TestType = v_m + v_t LocalVar%WE_Vw = v_m + v_t + ! LocalVar%WE_Vw = LPFilter(v_m + v_t,LocalVar%DT,0.5,LocalVar%iStatus,.FALSE.,objInst%instLPF) ENDIF ELSE @@ -274,7 +275,7 @@ REAL FUNCTION PeakShaving(LocalVar, CntrPar, objInst) ! V_towertop = PIController(LocalVar%FA_Acc, 0.0, 1.0, -100.00, 100.00, LocalVar%DT, 0.0, .FALSE., objInst%instPI) Vhat = LocalVar%WE_Vw - Vhatf = LPFilter(Vhat,LocalVar%DT,0.04,LocalVar%iStatus,.FALSE.,objInst%instLPF) + Vhatf = LPFilter(Vhat,LocalVar%DT,0.2,LocalVar%iStatus,.FALSE.,objInst%instLPF) LocalVar%TestType = Vhatf ! Define minimum blade pitch angle as a function of estimated wind speed PeakShaving = interp1d(CntrPar%PS_WindSpeeds, CntrPar%PS_BldPitchMin, Vhatf) diff --git a/DRC_Fortran/Source/Controllers.f90 b/DRC_Fortran/Source/Controllers.f90 index 855d1bb2d..2c2169be1 100644 --- a/DRC_Fortran/Source/Controllers.f90 +++ b/DRC_Fortran/Source/Controllers.f90 @@ -118,12 +118,12 @@ SUBROUTINE VariableSpeedControl(avrSWAP, CntrPar, LocalVar, objInst) IF (LocalVar%VS_State >= 4) THEN VS_MaxTq = CntrPar%VS_RtTq ELSE - ! VS_MaxTq = CntrPar%VS_MaxTq + ! VS_MaxTq = CntrPar%VS_MaxTq ! NJA: May want to boost max torque VS_MaxTq = CntrPar%VS_RtTq ENDIF LocalVar%GenTq = PIController(LocalVar%VS_SpdErr, CntrPar%VS_KP(1), CntrPar%VS_KI(1), CntrPar%VS_MinTq, VS_MaxTq, LocalVar%DT, CntrPar%VS_MaxOMTq, .FALSE., objInst%instPI) - ! K*Omega^2 control law with PI torque control in transition regions + ! K*Omega^2 control law with PI torque control in transition regions ELSE ! Update PI loops for region 1.5 and 2.5 PI control ! LocalVar%GenArTq = PIController(LocalVar%VS_SpdErrAr, CntrPar%VS_KP(1), CntrPar%VS_KI(1), CntrPar%VS_MaxOMTq, CntrPar%VS_ArSatTq, LocalVar%DT, CntrPar%VS_RtTq, .TRUE., objInst%instPI) diff --git a/DRC_Fortran/Source/DISCON.f90 b/DRC_Fortran/Source/DISCON.f90 index 67f162149..de8df7b77 100644 --- a/DRC_Fortran/Source/DISCON.f90 +++ b/DRC_Fortran/Source/DISCON.f90 @@ -39,6 +39,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME TYPE(LocalVariables), SAVE :: LocalVar TYPE(ObjectInstances), SAVE :: objInst TYPE(PerformanceData), SAVE :: PerfData + !------------------------------------------------------------------------------------------------------------------------------ ! Main control calculations !------------------------------------------------------------------------------------------------------------------------------ @@ -48,7 +49,7 @@ SUBROUTINE DISCON(avrSWAP, aviFAIL, accINFILE, avcOUTNAME, avcMSG) BIND (C, NAME CALL PreFilterMeasuredSignals(CntrPar, LocalVar, objInst) IF ((LocalVar%iStatus >= 0) .AND. (aviFAIL >= 0)) THEN ! Only compute control calculations if no error has occurred and we are not on the last time step - CALL ComputeVariablesSetpoints(CntrPar, LocalVar) + CALL ComputeVariablesSetpoints(CntrPar, LocalVar, objInst) CALL StateMachine(CntrPar, LocalVar) CALL WindSpeedEstimator(LocalVar, CntrPar, objInst, PerfData) diff --git a/DRC_Fortran/Source/DRC_Types.f90 b/DRC_Fortran/Source/DRC_Types.f90 index 69b8af80f..325fffc3e 100644 --- a/DRC_Fortran/Source/DRC_Types.f90 +++ b/DRC_Fortran/Source/DRC_Types.f90 @@ -52,6 +52,7 @@ MODULE DRC_Types INTEGER(4) :: VS_n ! Number of controller gains REAL(4), DIMENSION(:), ALLOCATABLE :: VS_KP ! Proportional gain for generator PI torque controller, used in the transitional 2.5 region REAL(4), DIMENSION(:), ALLOCATABLE :: VS_KI ! Integral gain for generator PI torque controller, used in the transitional 2.5 region + REAL(4) :: VS_TSRopt ! Power-maximizing region 2 tip-speed ratio [rad] INTEGER(4) :: SS_Mode ! Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} REAL(4) :: SS_VSGainBias ! Variable speed torque controller gain bias, [(rad/s)/rad]. diff --git a/DRC_Fortran/Source/ReadSetParameters.f90 b/DRC_Fortran/Source/ReadSetParameters.f90 index 8d7a43720..fd97fe76e 100644 --- a/DRC_Fortran/Source/ReadSetParameters.f90 +++ b/DRC_Fortran/Source/ReadSetParameters.f90 @@ -104,6 +104,7 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar) READ(UnControllerParameters,*) CntrPar%VS_KP ALLOCATE(CntrPar%VS_KI(CntrPar%VS_n)) READ(UnControllerParameters,*) CntrPar%VS_KI + READ(UnControllerParameters,*) CntrPar%VS_TSRopt READ(UnControllerParameters, *) !------- Setpoint Smoother -------------------------------- @@ -179,17 +180,20 @@ SUBROUTINE ReadControlParameterFileSub(CntrPar) END SUBROUTINE ReadControlParameterFileSub ! ----------------------------------------------------------------------------------- ! Calculate setpoints for primary control actions - SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar) - USE DRC_Types, ONLY : ControlParameters, LocalVariables + SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar, objInst) + USE DRC_Types, ONLY : ControlParameters, LocalVariables, ObjectInstances ! Allocate variables TYPE(ControlParameters), INTENT(INOUT) :: CntrPar TYPE(LocalVariables), INTENT(INOUT) :: LocalVar + TYPE(ObjectInstances), INTENT(INOUT) :: objInst + REAL(4) :: VS_RefSpd ! Referece speed for variable speed torque controller, [rad/s] REAL(4) :: PC_RefSpd ! Referece speed for pitch controller, [rad/s] REAL(4) :: Omega_op ! Optimal TSR-tracking generator speed, [rad/s] + REAL(4) :: WE_Vw_f ! Filtered Wind Speed Estimate ! temp - REAL(4) :: VS_TSRop = 7.5 + ! REAL(4) :: VS_TSRop = 7.5 ! ----- Calculate yaw misalignment error ----- LocalVar%Y_MErr = LocalVar%Y_M + CntrPar%Y_MErrSet ! Yaw-alignment error @@ -207,7 +211,8 @@ SUBROUTINE ComputeVariablesSetpoints(CntrPar, LocalVar) ! ----- Torque controller reference errors ----- ! Define VS reference generator speed [rad/s] IF (CntrPar%VS_ControlMode == 2) THEN - VS_RefSpd = (VS_TSRop * LocalVar%WE_Vw / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio + WE_Vw_f = LPFilter(LocalVar%We_Vw, LocalVar%DT, 0.1, LocalVar%iStatus, .FALSE., objInst%instLPF) + VS_RefSpd = (CntrPar%VS_TSRopt * WE_Vw_f / CntrPar%WE_BladeRadius) * CntrPar%WE_GearboxRatio VS_RefSpd = saturate(VS_RefSpd,CntrPar%VS_MinOMSpd, CntrPar%PC_RefSpd) ELSE VS_RefSpd = CntrPar%VS_RefSpd @@ -366,36 +371,38 @@ SUBROUTINE Assert(LocalVar, CntrPar, avrSWAP, aviFAIL, ErrMsg, size_avcMSG) ErrMsg = 'IPC_KI(2) must be zero or greater than zero.' ENDIF - IF (CntrPar%Y_IPC_omegaLP <= 0.0) THEN - aviFAIL = -1 - ErrMsg = 'Y_IPC_omegaLP must be greater than zero.' - ENDIF - - IF (CntrPar%Y_IPC_zetaLP <= 0.0) THEN - aviFAIL = -1 - ErrMsg = 'Y_IPC_zetaLP must be greater than zero.' - ENDIF - - IF (CntrPar%Y_ErrThresh <= 0.0) THEN - aviFAIL = -1 - ErrMsg = 'Y_ErrThresh must be greater than zero.' - ENDIF - - IF (CntrPar%Y_Rate <= 0.0) THEN - aviFAIL = -1 - ErrMsg = 'CntrPar%Y_Rate must be greater than zero.' - ENDIF - - IF (CntrPar%Y_omegaLPFast <= 0.0) THEN - aviFAIL = -1 - ErrMsg = 'Y_omegaLPFast must be greater than zero.' - ENDIF - - IF (CntrPar%Y_omegaLPSlow <= 0.0) THEN - aviFAIL = -1 - ErrMsg = 'Y_omegaLPSlow must be greater than zero.' + ! ---- Yaw Control ---- + IF (CntrPar%Y_ControlMode > 0) THEN + IF (CntrPar%Y_IPC_omegaLP <= 0.0) THEN + aviFAIL = -1 + ErrMsg = 'Y_IPC_omegaLP must be greater than zero.' + ENDIF + + IF (CntrPar%Y_IPC_zetaLP <= 0.0) THEN + aviFAIL = -1 + ErrMsg = 'Y_IPC_zetaLP must be greater than zero.' + ENDIF + + IF (CntrPar%Y_ErrThresh <= 0.0) THEN + aviFAIL = -1 + ErrMsg = 'Y_ErrThresh must be greater than zero.' + ENDIF + + IF (CntrPar%Y_Rate <= 0.0) THEN + aviFAIL = -1 + ErrMsg = 'CntrPar%Y_Rate must be greater than zero.' + ENDIF + + IF (CntrPar%Y_omegaLPFast <= 0.0) THEN + aviFAIL = -1 + ErrMsg = 'Y_omegaLPFast must be greater than zero.' + ENDIF + + IF (CntrPar%Y_omegaLPSlow <= 0.0) THEN + aviFAIL = -1 + ErrMsg = 'Y_omegaLPSlow must be greater than zero.' + ENDIF ENDIF - ! Abort if the user has not requested a pitch angle actuator (See Appendix A ! of Bladed User's Guide): IF (NINT(avrSWAP(10)) /= 0) THEN ! .TRUE. if a pitch angle actuator hasn't been requested diff --git a/Matlab_Toolbox/Post_TestCases.m b/Matlab_Toolbox/Post_TestCases.m index 321b00f81..aacea4e47 100644 --- a/Matlab_Toolbox/Post_TestCases.m +++ b/Matlab_Toolbox/Post_TestCases.m @@ -44,8 +44,13 @@ % Will want to (un)comment desired cases to plot % Usable Plot types: +<<<<<<< HEAD % - Step, Below Rated, Near Rated, Above Rated, Floating Steady, Floating Near Rated, Floating Mexican Hat plottype = 'Floating Above Rated'; +======= + % - Step, Below Rated, Near Rated, Above Rated, Floating Steady, Floating Near Rated, Floating Above Rated, Floating Mexican Hat +plottype = 'Near Rated'; +>>>>>>> dev_NewTurbines close all % Below Rated @@ -62,7 +67,11 @@ Pl_FastPlots(fo.OC4_ARsteady_Legacy, fo.OC4_ARsteady_Baseline) case 'Floating Near Rated' Pl_FastPlots(fo.OC4_NR_Legacy, fo.OC4_NR_Baseline) +<<<<<<< HEAD case 'Floating Above Rated' +======= + case 'Floating Above Rated' +>>>>>>> dev_NewTurbines Pl_FastPlots(fo.OC4_AR_Legacy, fo.OC4_AR_Baseline) case 'Floating Mexican Hat' Pl_FastPlots(fo.OC4_MH_Legacy, fo.OC4_MH_Baseline) diff --git a/Test_Cases/5MW_AR_Baseline/DISCON.IN b/Test_Cases/5MW_AR_Baseline/DISCON.IN index 99dee3c36..ef7726c15 100644 --- a/Test_Cases/5MW_AR_Baseline/DISCON.IN +++ b/Test_Cases/5MW_AR_Baseline/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the 5MW_Land wind turbine -! - File written using NREL Baseline Controller tuning logic on 10/01/19 +! - File written using NREL Baseline Controller tuning logic on 10/07/19 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file @@ -16,24 +16,24 @@ 1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} !------- FILTERS ---------------------------------------------------------- -1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +1.543417826848871 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] 0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] 0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] 0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.5 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [Hz]. !------- BLADE PITCH CONTROL ---------------------------------------------- -136 ! PC_GS_n - Amount of gain-scheduling table entries -0. 0.01843267 0.03012466 0.03938211 0.0473159 0.05438725 0.0608399 0.06682165 0.07243603 0.07774601 0.08280179 0.08764533 0.0922973 0.09678511 0.10113084 0.10534505 0.10944741 0.11344459 0.11734245 0.12115249 0.12488383 0.12853954 0.13212927 0.13565125 0.13911823 0.1425236 0.14587973 0.1491875 0.15244657 0.15566288 0.15883986 0.16197375 0.16506986 0.16813214 0.17115907 0.17415428 0.17711497 0.18004808 0.18295399 0.1858281 0.1886768 0.19150248 0.19430239 0.19707534 0.19983015 0.2025582 0.20526628 0.20795513 0.21062023 0.21326861 0.2158935 0.21850484 0.2210941 0.22366803 0.22622254 0.22876498 0.2312836 0.23379345 0.23628255 0.23875941 0.24122279 0.24366729 0.24610036 0.24852176 0.25092855 0.25332325 0.2557023 0.25807209 0.26042559 0.26276748 0.26510036 0.26742092 0.26973036 0.27202782 0.27431492 0.27658881 0.27885401 0.28110964 0.28336045 0.2855962 0.28782076 0.29003745 0.29224346 0.29444004 0.29663204 0.2988061 0.30097858 0.30314198 0.30529447 0.30743825 0.30958 0.31170708 0.31382687 0.31593631 0.3180419 0.32013786 0.32222978 0.32431029 0.32638663 0.32845309 0.33051357 0.33256802 0.33461455 0.33665611 0.33868284 0.34071023 0.34272963 0.34474196 0.34674528 0.34875073 0.35074041 0.35272695 0.35470654 0.35668277 0.35864961 0.36061312 0.36256798 0.36452117 0.36646633 0.36840178 0.37033735 0.3722649 0.37418622 0.37609996 0.37801477 0.37991806 0.38181864 0.38371323 0.38560453 0.38749153 0.38937202 0.39124103 0.39310673 0.39497577 0.39683082 0.39868511 ! PC_GS_angles - Gain-schedule table: pitch angles --0.02019147 -0.01950333 -0.01885443 -0.0182415 -0.01766165 -0.01711225 -0.01659098 -0.01609573 -0.01562459 -0.01517585 -0.01474794 -0.01433946 -0.0139491 -0.01357569 -0.01321814 -0.01287547 -0.01254676 -0.01223119 -0.01192797 -0.0116364 -0.01135581 -0.01108561 -0.01082521 -0.01057411 -0.0103318 -0.01009784 -0.00987181 -0.00965329 -0.00944194 -0.00923739 -0.00903933 -0.00884745 -0.00866147 -0.00848112 -0.00830614 -0.00813631 -0.0079714 -0.00781119 -0.00765549 -0.00750411 -0.00735688 -0.00721362 -0.00707417 -0.0069384 -0.00680614 -0.00667728 -0.00655167 -0.0064292 -0.00630975 -0.00619322 -0.00607949 -0.00596846 -0.00586005 -0.00575415 -0.00565069 -0.00554957 -0.00545073 -0.00535408 -0.00525955 -0.00516708 -0.00507659 -0.00498803 -0.00490133 -0.00481644 -0.00473329 -0.00465184 -0.00457204 -0.00449383 -0.00441716 -0.004342 -0.0042683 -0.00419602 -0.00412511 -0.00405553 -0.00398726 -0.00392025 -0.00385447 -0.00378988 -0.00372646 -0.00366417 -0.00360298 -0.00354286 -0.00348379 -0.00342574 -0.00336868 -0.00331258 -0.00325743 -0.00320319 -0.00314985 -0.00309739 -0.00304578 -0.002995 -0.00294503 -0.00289585 -0.00284745 -0.00279981 -0.0027529 -0.00270671 -0.00266123 -0.00261644 -0.00257232 -0.00252886 -0.00248604 -0.00244385 -0.00240228 -0.00236131 -0.00232093 -0.00228112 -0.00224188 -0.0022032 -0.00216505 -0.00212743 -0.00209033 -0.00205374 -0.00201765 -0.00198204 -0.00194691 -0.00191225 -0.00187805 -0.0018443 -0.00181099 -0.00177811 -0.00174566 -0.00171362 -0.00168199 -0.00165076 -0.00161992 -0.00158947 -0.00155939 -0.00152969 -0.00150035 -0.00147137 -0.00144274 -0.00141446 -0.00138651 -0.0013589 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains --0.00882307 -0.00856411 -0.00831992 -0.00808927 -0.00787106 -0.00766432 -0.00746816 -0.00728178 -0.00710449 -0.00693562 -0.0067746 -0.00662088 -0.00647398 -0.00633346 -0.00619891 -0.00606996 -0.00594626 -0.00582751 -0.0057134 -0.00560368 -0.00549809 -0.00539641 -0.00529842 -0.00520393 -0.00511274 -0.0050247 -0.00493964 -0.00485741 -0.00477787 -0.0047009 -0.00462637 -0.00455416 -0.00448417 -0.0044163 -0.00435046 -0.00428655 -0.00422449 -0.0041642 -0.00410561 -0.00404864 -0.00399324 -0.00393933 -0.00388685 -0.00383576 -0.00378599 -0.00373749 -0.00369023 -0.00364414 -0.00359919 -0.00355534 -0.00351254 -0.00347076 -0.00342996 -0.00339011 -0.00335117 -0.00331312 -0.00327593 -0.00323956 -0.00320399 -0.00316919 -0.00313514 -0.00310181 -0.00306918 -0.00303724 -0.00300595 -0.0029753 -0.00294526 -0.00291583 -0.00288698 -0.0028587 -0.00283096 -0.00280376 -0.00277708 -0.0027509 -0.0027252 -0.00269999 -0.00267523 -0.00265093 -0.00262706 -0.00260362 -0.00258059 -0.00255797 -0.00253574 -0.0025139 -0.00249242 -0.00247131 -0.00245056 -0.00243015 -0.00241008 -0.00239033 -0.00237091 -0.0023518 -0.002333 -0.00231449 -0.00229628 -0.00227835 -0.0022607 -0.00224332 -0.0022262 -0.00220935 -0.00219274 -0.00217639 -0.00216028 -0.0021444 -0.00212876 -0.00211334 -0.00209814 -0.00208316 -0.0020684 -0.00205384 -0.00203948 -0.00202533 -0.00201136 -0.00199759 -0.00198401 -0.00197061 -0.00195739 -0.00194435 -0.00193148 -0.00191878 -0.00190624 -0.00189387 -0.00188166 -0.0018696 -0.0018577 -0.00184595 -0.00183434 -0.00182288 -0.00181157 -0.00180039 -0.00178935 -0.00177844 -0.00176767 -0.00175702 -0.00174651 -0.00173612 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +27 ! PC_GS_n - Amount of gain-scheduling table entries +0.05852874 0.08586931 0.10789716 0.1271165 0.14453395 0.16067791 0.17585826 0.19027256 0.20405942 0.21730904 0.23010311 0.24249689 0.2545414 0.26626371 0.27770397 0.28889173 0.29983774 0.31057221 0.32109644 0.33144053 0.34160524 0.35160739 0.36145513 0.37115299 0.38071093 0.3901412 0.39943831 ! PC_GS_angles - Gain-schedule table: pitch angles +-0.01603382 -0.01396602 -0.01229584 -0.01091865 -0.00976358 -0.00878088 -0.00793467 -0.00719835 -0.00655181 -0.00597959 -0.00546956 -0.00501211 -0.00459951 -0.00422546 -0.00388481 -0.00357328 -0.00328728 -0.0030238 -0.00278028 -0.00255453 -0.00234468 -0.00214911 -0.0019664 -0.00179533 -0.00163481 -0.00148391 -0.00134179 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-0.00715561 -0.00639445 -0.00577965 -0.00527271 -0.00484752 -0.00448579 -0.0041743 -0.00390326 -0.00366527 -0.00345463 -0.00326689 -0.0030985 -0.00294662 -0.00280893 -0.00268354 -0.00256886 -0.00246359 -0.0023666 -0.00227696 -0.00219386 -0.00211661 -0.00204462 -0.00197737 -0.0019144 -0.00185531 -0.00179976 -0.00174745 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +122.90957658394467 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. 0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] 0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] @@ -41,63 +41,64 @@ 0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] -1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. -2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] +0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] !------- VS TORQUE CONTROL ------------------------------------------------ -0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] -43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +94.4 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +43093.55150917838 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +47402.906660096225 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. -91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] -2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] -5.0E+06 ! VS_RtPwr - Wind turbine rated power [W] -43093.55 ! VS_RtTq - Rated torque, [Nm]. -120.113 ! VS_RefSpd - Rated generator speed [rad/s] +0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5000000 ! VS_RtPwr - Wind turbine rated power [W] +43093.55150917838 ! VS_RtTq - Rated torque, [Nm]. +122.90957658394467 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-889.094048017944 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-172.0461874545648 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.4 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. !------- SETPOINT SMOOTHER --------------------------------------------- 30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. 0.001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. !------- WIND SPEED ESTIMATOR --------------------------------------------- -63.0 ! WE_BladeRadius - Blade length [m] +63.0 ! WE_BladeRadius - Blade length [m] 4 ! WE_CP_n - Amount of parameters in the Cp array -14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function -20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] -97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +40469564.444 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1.225 ! WE_RhoAir - Air density, [kg m^-3] "../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) -320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -23 ! WE_FOPoles_N - Number of first-order system poles used in EKF -3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles +320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +42 ! WE_FOPoles_N - Number of first-order system poles used in EKF + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02665071 -0.02998205 -0.03331339 -0.03664473 -0.03997606 -0.0433074 -0.04663874 -0.04997008 -0.05330142 -0.05663276 -0.0599641 -0.06329543 -0.06662677 -0.06995811 -0.07328945 -0.06321278 -0.07469151 -0.08828579 -0.10297822 -0.11842623 -0.13448765 -0.15120764 -0.168455 -0.18635293 -0.20483641 -0.22395323 -0.24348262 -0.26365771 -0.2842596 -0.30535287 -0.32683352 -0.3487705 -0.37113879 -0.39376001 -0.41675049 -0.44017539 -0.46432564 -0.4888057 -0.51273708 -0.53554138 -0.55932133 -0.58645605 ! WE_FOPoles - First order system poles !------- YAW CONTROL ------------------------------------------------------ -1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] -0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) --0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp --0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki -0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. -1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. -0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad] -1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] -0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] -0.0034906 ! Y_Rate - Yaw rate [rad/s] +0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.0 ! Y_MErrSet - Yaw alignment error, set point [rad] +0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0 ! Y_Rate - Yaw rate [rad/s] !------- TOWER FORE-AFT DAMPING ------------------------------------------- -1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag -0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] -0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] +0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] !------- PEAK SHAVING ------------------------------------------- -210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) - 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.02962541 -0.02230897 -0.01548946 -0.00915689 -0.00323985 0.00231633 0.00755924 0.01252064 0.01723337 0.02171883 0.02600713 0.03010809 0.03403543 0.03780094 0.04141197 0.0448834 0.04301121 0.04572902 0.04841563 0.05107257 0.05370175 0.05630738 0.05888727 0.06144604 0.06398009 0.06649806 0.06899513 0.07147461 0.07393783 0.0763848 0.07881322 0.08122765 0.08363032 0.08601684 0.0883911 0.09075519 0.09310191 0.09543925 0.09776725 0.10008031 0.1023843 0.10467939 0.10696282 0.10923552 0.11150342 0.11375564 0.11600427 0.118243 0.12047296 0.12269376 0.12490488 0.12711415 0.12931036 0.13150096 0.13368154 0.13585982 0.13803009 0.14018961 0.14234359 0.14449503 0.14663648 0.14877236 0.15089947 0.15302471 0.155141 0.15725402 0.15935959 0.16145813 0.16355132 0.16563963 0.16772494 0.1698033 0.17187555 0.17394191 0.17600722 0.17806499 0.18011745 0.18216164 0.18420446 0.18624091 0.18827655 0.19030833 0.19233052 0.19434885 0.19636357 0.19837593 0.20037883 0.20238383 0.20438058 0.20637502 0.20836358 0.21034732 0.21232885 0.21430571 0.21627763 0.21824694 0.22021326 0.22217222 0.22412743 0.22608217 0.22803347 0.22998291 0.23192295 0.23385759 0.23579759 0.23772869 0.23965799 0.24157841 0.24349944 0.24541689 0.24733152 0.24924241 0.25115108 0.25305646 0.25495687 0.25685379 0.25874221 0.26063593 0.26252242 0.26440664 0.26628698 0.26816398 0.27004031 0.27191147 0.27377527 0.27564404 0.27750921 0.27935984 0.28121741 0.28306997 0.2849209 0.28676631 0.28860828 0.29045122 0.29229007 0.29412417 0.29595331 0.29778415 0.29960719 0.30142759 0.30324755 0.30506054 0.30687771 0.30869136 0.31049896 0.31230004 0.31410149 0.3159051 0.3177027 0.31949741 0.32128578 0.32306955 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +42 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03275873 0.00083377 0.02543348 0.0448834 0.0667768 0.07915202 0.09113854 0.10280435 0.11420819 0.12538567 0.13636556 0.14716567 0.15780447 0.1683014 0.178663 0.18889865 0.19901765 0.20902392 0.21892797 0.22873221 0.23844548 0.24806675 0.25759734 0.26705022 0.27641741 0.2857055 0.29491896 0.3040543 0.31311378 0.32210299 0.33103247 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/Test_Cases/5MW_BR_Baseline/DISCON.IN b/Test_Cases/5MW_BR_Baseline/DISCON.IN index 12916d09c..6d38f170e 100644 --- a/Test_Cases/5MW_BR_Baseline/DISCON.IN +++ b/Test_Cases/5MW_BR_Baseline/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the 5MW_Land wind turbine -! - File written using NREL Baseline Controller tuning logic on 10/01/19 +! - File written using NREL Baseline Controller tuning logic on 10/07/19 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file @@ -16,24 +16,24 @@ 1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} !------- FILTERS ---------------------------------------------------------- -1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +1.543417826848871 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] 0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] 0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] 0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.5 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [Hz]. !------- BLADE PITCH CONTROL ---------------------------------------------- -136 ! PC_GS_n - Amount of gain-scheduling table entries -0. 0.01843267 0.03012466 0.03938211 0.0473159 0.05438725 0.0608399 0.06682165 0.07243603 0.07774601 0.08280179 0.08764533 0.0922973 0.09678511 0.10113084 0.10534505 0.10944741 0.11344459 0.11734245 0.12115249 0.12488383 0.12853954 0.13212927 0.13565125 0.13911823 0.1425236 0.14587973 0.1491875 0.15244657 0.15566288 0.15883986 0.16197375 0.16506986 0.16813214 0.17115907 0.17415428 0.17711497 0.18004808 0.18295399 0.1858281 0.1886768 0.19150248 0.19430239 0.19707534 0.19983015 0.2025582 0.20526628 0.20795513 0.21062023 0.21326861 0.2158935 0.21850484 0.2210941 0.22366803 0.22622254 0.22876498 0.2312836 0.23379345 0.23628255 0.23875941 0.24122279 0.24366729 0.24610036 0.24852176 0.25092855 0.25332325 0.2557023 0.25807209 0.26042559 0.26276748 0.26510036 0.26742092 0.26973036 0.27202782 0.27431492 0.27658881 0.27885401 0.28110964 0.28336045 0.2855962 0.28782076 0.29003745 0.29224346 0.29444004 0.29663204 0.2988061 0.30097858 0.30314198 0.30529447 0.30743825 0.30958 0.31170708 0.31382687 0.31593631 0.3180419 0.32013786 0.32222978 0.32431029 0.32638663 0.32845309 0.33051357 0.33256802 0.33461455 0.33665611 0.33868284 0.34071023 0.34272963 0.34474196 0.34674528 0.34875073 0.35074041 0.35272695 0.35470654 0.35668277 0.35864961 0.36061312 0.36256798 0.36452117 0.36646633 0.36840178 0.37033735 0.3722649 0.37418622 0.37609996 0.37801477 0.37991806 0.38181864 0.38371323 0.38560453 0.38749153 0.38937202 0.39124103 0.39310673 0.39497577 0.39683082 0.39868511 ! PC_GS_angles - Gain-schedule table: pitch angles --0.02019147 -0.01950333 -0.01885443 -0.0182415 -0.01766165 -0.01711225 -0.01659098 -0.01609573 -0.01562459 -0.01517585 -0.01474794 -0.01433946 -0.0139491 -0.01357569 -0.01321814 -0.01287547 -0.01254676 -0.01223119 -0.01192797 -0.0116364 -0.01135581 -0.01108561 -0.01082521 -0.01057411 -0.0103318 -0.01009784 -0.00987181 -0.00965329 -0.00944194 -0.00923739 -0.00903933 -0.00884745 -0.00866147 -0.00848112 -0.00830614 -0.00813631 -0.0079714 -0.00781119 -0.00765549 -0.00750411 -0.00735688 -0.00721362 -0.00707417 -0.0069384 -0.00680614 -0.00667728 -0.00655167 -0.0064292 -0.00630975 -0.00619322 -0.00607949 -0.00596846 -0.00586005 -0.00575415 -0.00565069 -0.00554957 -0.00545073 -0.00535408 -0.00525955 -0.00516708 -0.00507659 -0.00498803 -0.00490133 -0.00481644 -0.00473329 -0.00465184 -0.00457204 -0.00449383 -0.00441716 -0.004342 -0.0042683 -0.00419602 -0.00412511 -0.00405553 -0.00398726 -0.00392025 -0.00385447 -0.00378988 -0.00372646 -0.00366417 -0.00360298 -0.00354286 -0.00348379 -0.00342574 -0.00336868 -0.00331258 -0.00325743 -0.00320319 -0.00314985 -0.00309739 -0.00304578 -0.002995 -0.00294503 -0.00289585 -0.00284745 -0.00279981 -0.0027529 -0.00270671 -0.00266123 -0.00261644 -0.00257232 -0.00252886 -0.00248604 -0.00244385 -0.00240228 -0.00236131 -0.00232093 -0.00228112 -0.00224188 -0.0022032 -0.00216505 -0.00212743 -0.00209033 -0.00205374 -0.00201765 -0.00198204 -0.00194691 -0.00191225 -0.00187805 -0.0018443 -0.00181099 -0.00177811 -0.00174566 -0.00171362 -0.00168199 -0.00165076 -0.00161992 -0.00158947 -0.00155939 -0.00152969 -0.00150035 -0.00147137 -0.00144274 -0.00141446 -0.00138651 -0.0013589 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains --0.00882307 -0.00856411 -0.00831992 -0.00808927 -0.00787106 -0.00766432 -0.00746816 -0.00728178 -0.00710449 -0.00693562 -0.0067746 -0.00662088 -0.00647398 -0.00633346 -0.00619891 -0.00606996 -0.00594626 -0.00582751 -0.0057134 -0.00560368 -0.00549809 -0.00539641 -0.00529842 -0.00520393 -0.00511274 -0.0050247 -0.00493964 -0.00485741 -0.00477787 -0.0047009 -0.00462637 -0.00455416 -0.00448417 -0.0044163 -0.00435046 -0.00428655 -0.00422449 -0.0041642 -0.00410561 -0.00404864 -0.00399324 -0.00393933 -0.00388685 -0.00383576 -0.00378599 -0.00373749 -0.00369023 -0.00364414 -0.00359919 -0.00355534 -0.00351254 -0.00347076 -0.00342996 -0.00339011 -0.00335117 -0.00331312 -0.00327593 -0.00323956 -0.00320399 -0.00316919 -0.00313514 -0.00310181 -0.00306918 -0.00303724 -0.00300595 -0.0029753 -0.00294526 -0.00291583 -0.00288698 -0.0028587 -0.00283096 -0.00280376 -0.00277708 -0.0027509 -0.0027252 -0.00269999 -0.00267523 -0.00265093 -0.00262706 -0.00260362 -0.00258059 -0.00255797 -0.00253574 -0.0025139 -0.00249242 -0.00247131 -0.00245056 -0.00243015 -0.00241008 -0.00239033 -0.00237091 -0.0023518 -0.002333 -0.00231449 -0.00229628 -0.00227835 -0.0022607 -0.00224332 -0.0022262 -0.00220935 -0.00219274 -0.00217639 -0.00216028 -0.0021444 -0.00212876 -0.00211334 -0.00209814 -0.00208316 -0.0020684 -0.00205384 -0.00203948 -0.00202533 -0.00201136 -0.00199759 -0.00198401 -0.00197061 -0.00195739 -0.00194435 -0.00193148 -0.00191878 -0.00190624 -0.00189387 -0.00188166 -0.0018696 -0.0018577 -0.00184595 -0.00183434 -0.00182288 -0.00181157 -0.00180039 -0.00178935 -0.00177844 -0.00176767 -0.00175702 -0.00174651 -0.00173612 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +27 ! PC_GS_n - Amount of gain-scheduling table entries +0.05852874 0.08586931 0.10789716 0.1271165 0.14453395 0.16067791 0.17585826 0.19027256 0.20405942 0.21730904 0.23010311 0.24249689 0.2545414 0.26626371 0.27770397 0.28889173 0.29983774 0.31057221 0.32109644 0.33144053 0.34160524 0.35160739 0.36145513 0.37115299 0.38071093 0.3901412 0.39943831 ! PC_GS_angles - Gain-schedule table: pitch angles +-0.01603382 -0.01396602 -0.01229584 -0.01091865 -0.00976358 -0.00878088 -0.00793467 -0.00719835 -0.00655181 -0.00597959 -0.00546956 -0.00501211 -0.00459951 -0.00422546 -0.00388481 -0.00357328 -0.00328728 -0.0030238 -0.00278028 -0.00255453 -0.00234468 -0.00214911 -0.0019664 -0.00179533 -0.00163481 -0.00148391 -0.00134179 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-0.00715561 -0.00639445 -0.00577965 -0.00527271 -0.00484752 -0.00448579 -0.0041743 -0.00390326 -0.00366527 -0.00345463 -0.00326689 -0.0030985 -0.00294662 -0.00280893 -0.00268354 -0.00256886 -0.00246359 -0.0023666 -0.00227696 -0.00219386 -0.00211661 -0.00204462 -0.00197737 -0.0019144 -0.00185531 -0.00179976 -0.00174745 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +122.90957658394467 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. 0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] 0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] @@ -41,63 +41,64 @@ 0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] -1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. -2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] +0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] !------- VS TORQUE CONTROL ------------------------------------------------ -0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] -43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +94.4 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +43093.55150917838 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +47402.906660096225 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. -91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] -2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] -5.0E+06 ! VS_RtPwr - Wind turbine rated power [W] -43093.55 ! VS_RtTq - Rated torque, [Nm]. -120.113 ! VS_RefSpd - Rated generator speed [rad/s] +0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5000000 ! VS_RtPwr - Wind turbine rated power [W] +43093.55150917838 ! VS_RtTq - Rated torque, [Nm]. +122.90957658394467 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-889.094048017944 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-172.0461874545648 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.4 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. !------- SETPOINT SMOOTHER --------------------------------------------- 30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. 0.0001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. !------- WIND SPEED ESTIMATOR --------------------------------------------- -63.0 ! WE_BladeRadius - Blade length [m] +63.0 ! WE_BladeRadius - Blade length [m] 4 ! WE_CP_n - Amount of parameters in the Cp array -14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function -20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] -97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +40469564.444 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1.225 ! WE_RhoAir - Air density, [kg m^-3] "../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) -320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -23 ! WE_FOPoles_N - Number of first-order system poles used in EKF -3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles +320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +42 ! WE_FOPoles_N - Number of first-order system poles used in EKF + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02665071 -0.02998205 -0.03331339 -0.03664473 -0.03997606 -0.0433074 -0.04663874 -0.04997008 -0.05330142 -0.05663276 -0.0599641 -0.06329543 -0.06662677 -0.06995811 -0.07328945 -0.06321278 -0.07469151 -0.08828579 -0.10297822 -0.11842623 -0.13448765 -0.15120764 -0.168455 -0.18635293 -0.20483641 -0.22395323 -0.24348262 -0.26365771 -0.2842596 -0.30535287 -0.32683352 -0.3487705 -0.37113879 -0.39376001 -0.41675049 -0.44017539 -0.46432564 -0.4888057 -0.51273708 -0.53554138 -0.55932133 -0.58645605 ! WE_FOPoles - First order system poles !------- YAW CONTROL ------------------------------------------------------ -1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] -0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) --0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp --0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki -0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. -1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. -0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad] -1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] -0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] -0.0034906 ! Y_Rate - Yaw rate [rad/s] +0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.0 ! Y_MErrSet - Yaw alignment error, set point [rad] +0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0 ! Y_Rate - Yaw rate [rad/s] !------- TOWER FORE-AFT DAMPING ------------------------------------------- -1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag -0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] -0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] +0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] !------- PEAK SHAVING ------------------------------------------- -210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) - 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.02962541 -0.02230897 -0.01548946 -0.00915689 -0.00323985 0.00231633 0.00755924 0.01252064 0.01723337 0.02171883 0.02600713 0.03010809 0.03403543 0.03780094 0.04141197 0.0448834 0.04301121 0.04572902 0.04841563 0.05107257 0.05370175 0.05630738 0.05888727 0.06144604 0.06398009 0.06649806 0.06899513 0.07147461 0.07393783 0.0763848 0.07881322 0.08122765 0.08363032 0.08601684 0.0883911 0.09075519 0.09310191 0.09543925 0.09776725 0.10008031 0.1023843 0.10467939 0.10696282 0.10923552 0.11150342 0.11375564 0.11600427 0.118243 0.12047296 0.12269376 0.12490488 0.12711415 0.12931036 0.13150096 0.13368154 0.13585982 0.13803009 0.14018961 0.14234359 0.14449503 0.14663648 0.14877236 0.15089947 0.15302471 0.155141 0.15725402 0.15935959 0.16145813 0.16355132 0.16563963 0.16772494 0.1698033 0.17187555 0.17394191 0.17600722 0.17806499 0.18011745 0.18216164 0.18420446 0.18624091 0.18827655 0.19030833 0.19233052 0.19434885 0.19636357 0.19837593 0.20037883 0.20238383 0.20438058 0.20637502 0.20836358 0.21034732 0.21232885 0.21430571 0.21627763 0.21824694 0.22021326 0.22217222 0.22412743 0.22608217 0.22803347 0.22998291 0.23192295 0.23385759 0.23579759 0.23772869 0.23965799 0.24157841 0.24349944 0.24541689 0.24733152 0.24924241 0.25115108 0.25305646 0.25495687 0.25685379 0.25874221 0.26063593 0.26252242 0.26440664 0.26628698 0.26816398 0.27004031 0.27191147 0.27377527 0.27564404 0.27750921 0.27935984 0.28121741 0.28306997 0.2849209 0.28676631 0.28860828 0.29045122 0.29229007 0.29412417 0.29595331 0.29778415 0.29960719 0.30142759 0.30324755 0.30506054 0.30687771 0.30869136 0.31049896 0.31230004 0.31410149 0.3159051 0.3177027 0.31949741 0.32128578 0.32306955 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +42 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03275873 0.00083377 0.02543348 0.0448834 0.0667768 0.07915202 0.09113854 0.10280435 0.11420819 0.12538567 0.13636556 0.14716567 0.15780447 0.1683014 0.178663 0.18889865 0.19901765 0.20902392 0.21892797 0.22873221 0.23844548 0.24806675 0.25759734 0.26705022 0.27641741 0.2857055 0.29491896 0.3040543 0.31311378 0.32210299 0.33103247 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/Test_Cases/5MW_Baseline/DISCON.IN b/Test_Cases/5MW_Baseline/DISCON.IN index 99dee3c36..ef7726c15 100644 --- a/Test_Cases/5MW_Baseline/DISCON.IN +++ b/Test_Cases/5MW_Baseline/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the 5MW_Land wind turbine -! - File written using NREL Baseline Controller tuning logic on 10/01/19 +! - File written using NREL Baseline Controller tuning logic on 10/07/19 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file @@ -16,24 +16,24 @@ 1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} !------- FILTERS ---------------------------------------------------------- -1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +1.543417826848871 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] 0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] 0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] 0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.5 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [Hz]. !------- BLADE PITCH CONTROL ---------------------------------------------- -136 ! PC_GS_n - Amount of gain-scheduling table entries -0. 0.01843267 0.03012466 0.03938211 0.0473159 0.05438725 0.0608399 0.06682165 0.07243603 0.07774601 0.08280179 0.08764533 0.0922973 0.09678511 0.10113084 0.10534505 0.10944741 0.11344459 0.11734245 0.12115249 0.12488383 0.12853954 0.13212927 0.13565125 0.13911823 0.1425236 0.14587973 0.1491875 0.15244657 0.15566288 0.15883986 0.16197375 0.16506986 0.16813214 0.17115907 0.17415428 0.17711497 0.18004808 0.18295399 0.1858281 0.1886768 0.19150248 0.19430239 0.19707534 0.19983015 0.2025582 0.20526628 0.20795513 0.21062023 0.21326861 0.2158935 0.21850484 0.2210941 0.22366803 0.22622254 0.22876498 0.2312836 0.23379345 0.23628255 0.23875941 0.24122279 0.24366729 0.24610036 0.24852176 0.25092855 0.25332325 0.2557023 0.25807209 0.26042559 0.26276748 0.26510036 0.26742092 0.26973036 0.27202782 0.27431492 0.27658881 0.27885401 0.28110964 0.28336045 0.2855962 0.28782076 0.29003745 0.29224346 0.29444004 0.29663204 0.2988061 0.30097858 0.30314198 0.30529447 0.30743825 0.30958 0.31170708 0.31382687 0.31593631 0.3180419 0.32013786 0.32222978 0.32431029 0.32638663 0.32845309 0.33051357 0.33256802 0.33461455 0.33665611 0.33868284 0.34071023 0.34272963 0.34474196 0.34674528 0.34875073 0.35074041 0.35272695 0.35470654 0.35668277 0.35864961 0.36061312 0.36256798 0.36452117 0.36646633 0.36840178 0.37033735 0.3722649 0.37418622 0.37609996 0.37801477 0.37991806 0.38181864 0.38371323 0.38560453 0.38749153 0.38937202 0.39124103 0.39310673 0.39497577 0.39683082 0.39868511 ! PC_GS_angles - Gain-schedule table: pitch angles --0.02019147 -0.01950333 -0.01885443 -0.0182415 -0.01766165 -0.01711225 -0.01659098 -0.01609573 -0.01562459 -0.01517585 -0.01474794 -0.01433946 -0.0139491 -0.01357569 -0.01321814 -0.01287547 -0.01254676 -0.01223119 -0.01192797 -0.0116364 -0.01135581 -0.01108561 -0.01082521 -0.01057411 -0.0103318 -0.01009784 -0.00987181 -0.00965329 -0.00944194 -0.00923739 -0.00903933 -0.00884745 -0.00866147 -0.00848112 -0.00830614 -0.00813631 -0.0079714 -0.00781119 -0.00765549 -0.00750411 -0.00735688 -0.00721362 -0.00707417 -0.0069384 -0.00680614 -0.00667728 -0.00655167 -0.0064292 -0.00630975 -0.00619322 -0.00607949 -0.00596846 -0.00586005 -0.00575415 -0.00565069 -0.00554957 -0.00545073 -0.00535408 -0.00525955 -0.00516708 -0.00507659 -0.00498803 -0.00490133 -0.00481644 -0.00473329 -0.00465184 -0.00457204 -0.00449383 -0.00441716 -0.004342 -0.0042683 -0.00419602 -0.00412511 -0.00405553 -0.00398726 -0.00392025 -0.00385447 -0.00378988 -0.00372646 -0.00366417 -0.00360298 -0.00354286 -0.00348379 -0.00342574 -0.00336868 -0.00331258 -0.00325743 -0.00320319 -0.00314985 -0.00309739 -0.00304578 -0.002995 -0.00294503 -0.00289585 -0.00284745 -0.00279981 -0.0027529 -0.00270671 -0.00266123 -0.00261644 -0.00257232 -0.00252886 -0.00248604 -0.00244385 -0.00240228 -0.00236131 -0.00232093 -0.00228112 -0.00224188 -0.0022032 -0.00216505 -0.00212743 -0.00209033 -0.00205374 -0.00201765 -0.00198204 -0.00194691 -0.00191225 -0.00187805 -0.0018443 -0.00181099 -0.00177811 -0.00174566 -0.00171362 -0.00168199 -0.00165076 -0.00161992 -0.00158947 -0.00155939 -0.00152969 -0.00150035 -0.00147137 -0.00144274 -0.00141446 -0.00138651 -0.0013589 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains --0.00882307 -0.00856411 -0.00831992 -0.00808927 -0.00787106 -0.00766432 -0.00746816 -0.00728178 -0.00710449 -0.00693562 -0.0067746 -0.00662088 -0.00647398 -0.00633346 -0.00619891 -0.00606996 -0.00594626 -0.00582751 -0.0057134 -0.00560368 -0.00549809 -0.00539641 -0.00529842 -0.00520393 -0.00511274 -0.0050247 -0.00493964 -0.00485741 -0.00477787 -0.0047009 -0.00462637 -0.00455416 -0.00448417 -0.0044163 -0.00435046 -0.00428655 -0.00422449 -0.0041642 -0.00410561 -0.00404864 -0.00399324 -0.00393933 -0.00388685 -0.00383576 -0.00378599 -0.00373749 -0.00369023 -0.00364414 -0.00359919 -0.00355534 -0.00351254 -0.00347076 -0.00342996 -0.00339011 -0.00335117 -0.00331312 -0.00327593 -0.00323956 -0.00320399 -0.00316919 -0.00313514 -0.00310181 -0.00306918 -0.00303724 -0.00300595 -0.0029753 -0.00294526 -0.00291583 -0.00288698 -0.0028587 -0.00283096 -0.00280376 -0.00277708 -0.0027509 -0.0027252 -0.00269999 -0.00267523 -0.00265093 -0.00262706 -0.00260362 -0.00258059 -0.00255797 -0.00253574 -0.0025139 -0.00249242 -0.00247131 -0.00245056 -0.00243015 -0.00241008 -0.00239033 -0.00237091 -0.0023518 -0.002333 -0.00231449 -0.00229628 -0.00227835 -0.0022607 -0.00224332 -0.0022262 -0.00220935 -0.00219274 -0.00217639 -0.00216028 -0.0021444 -0.00212876 -0.00211334 -0.00209814 -0.00208316 -0.0020684 -0.00205384 -0.00203948 -0.00202533 -0.00201136 -0.00199759 -0.00198401 -0.00197061 -0.00195739 -0.00194435 -0.00193148 -0.00191878 -0.00190624 -0.00189387 -0.00188166 -0.0018696 -0.0018577 -0.00184595 -0.00183434 -0.00182288 -0.00181157 -0.00180039 -0.00178935 -0.00177844 -0.00176767 -0.00175702 -0.00174651 -0.00173612 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +27 ! PC_GS_n - Amount of gain-scheduling table entries +0.05852874 0.08586931 0.10789716 0.1271165 0.14453395 0.16067791 0.17585826 0.19027256 0.20405942 0.21730904 0.23010311 0.24249689 0.2545414 0.26626371 0.27770397 0.28889173 0.29983774 0.31057221 0.32109644 0.33144053 0.34160524 0.35160739 0.36145513 0.37115299 0.38071093 0.3901412 0.39943831 ! PC_GS_angles - Gain-schedule table: pitch angles +-0.01603382 -0.01396602 -0.01229584 -0.01091865 -0.00976358 -0.00878088 -0.00793467 -0.00719835 -0.00655181 -0.00597959 -0.00546956 -0.00501211 -0.00459951 -0.00422546 -0.00388481 -0.00357328 -0.00328728 -0.0030238 -0.00278028 -0.00255453 -0.00234468 -0.00214911 -0.0019664 -0.00179533 -0.00163481 -0.00148391 -0.00134179 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-0.00715561 -0.00639445 -0.00577965 -0.00527271 -0.00484752 -0.00448579 -0.0041743 -0.00390326 -0.00366527 -0.00345463 -0.00326689 -0.0030985 -0.00294662 -0.00280893 -0.00268354 -0.00256886 -0.00246359 -0.0023666 -0.00227696 -0.00219386 -0.00211661 -0.00204462 -0.00197737 -0.0019144 -0.00185531 -0.00179976 -0.00174745 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +122.90957658394467 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. 0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] 0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] @@ -41,63 +41,64 @@ 0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] -1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. -2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] +0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] !------- VS TORQUE CONTROL ------------------------------------------------ -0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] -43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +94.4 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +43093.55150917838 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +47402.906660096225 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. -91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] -2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] -5.0E+06 ! VS_RtPwr - Wind turbine rated power [W] -43093.55 ! VS_RtTq - Rated torque, [Nm]. -120.113 ! VS_RefSpd - Rated generator speed [rad/s] +0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5000000 ! VS_RtPwr - Wind turbine rated power [W] +43093.55150917838 ! VS_RtTq - Rated torque, [Nm]. +122.90957658394467 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-889.094048017944 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-172.0461874545648 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.4 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. !------- SETPOINT SMOOTHER --------------------------------------------- 30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. 0.001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. !------- WIND SPEED ESTIMATOR --------------------------------------------- -63.0 ! WE_BladeRadius - Blade length [m] +63.0 ! WE_BladeRadius - Blade length [m] 4 ! WE_CP_n - Amount of parameters in the Cp array -14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function -20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] -97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +40469564.444 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1.225 ! WE_RhoAir - Air density, [kg m^-3] "../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) -320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -23 ! WE_FOPoles_N - Number of first-order system poles used in EKF -3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles +320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +42 ! WE_FOPoles_N - Number of first-order system poles used in EKF + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02665071 -0.02998205 -0.03331339 -0.03664473 -0.03997606 -0.0433074 -0.04663874 -0.04997008 -0.05330142 -0.05663276 -0.0599641 -0.06329543 -0.06662677 -0.06995811 -0.07328945 -0.06321278 -0.07469151 -0.08828579 -0.10297822 -0.11842623 -0.13448765 -0.15120764 -0.168455 -0.18635293 -0.20483641 -0.22395323 -0.24348262 -0.26365771 -0.2842596 -0.30535287 -0.32683352 -0.3487705 -0.37113879 -0.39376001 -0.41675049 -0.44017539 -0.46432564 -0.4888057 -0.51273708 -0.53554138 -0.55932133 -0.58645605 ! WE_FOPoles - First order system poles !------- YAW CONTROL ------------------------------------------------------ -1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] -0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) --0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp --0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki -0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. -1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. -0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad] -1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] -0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] -0.0034906 ! Y_Rate - Yaw rate [rad/s] +0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.0 ! Y_MErrSet - Yaw alignment error, set point [rad] +0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0 ! Y_Rate - Yaw rate [rad/s] !------- TOWER FORE-AFT DAMPING ------------------------------------------- -1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag -0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] -0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] +0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] !------- PEAK SHAVING ------------------------------------------- -210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) - 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.02962541 -0.02230897 -0.01548946 -0.00915689 -0.00323985 0.00231633 0.00755924 0.01252064 0.01723337 0.02171883 0.02600713 0.03010809 0.03403543 0.03780094 0.04141197 0.0448834 0.04301121 0.04572902 0.04841563 0.05107257 0.05370175 0.05630738 0.05888727 0.06144604 0.06398009 0.06649806 0.06899513 0.07147461 0.07393783 0.0763848 0.07881322 0.08122765 0.08363032 0.08601684 0.0883911 0.09075519 0.09310191 0.09543925 0.09776725 0.10008031 0.1023843 0.10467939 0.10696282 0.10923552 0.11150342 0.11375564 0.11600427 0.118243 0.12047296 0.12269376 0.12490488 0.12711415 0.12931036 0.13150096 0.13368154 0.13585982 0.13803009 0.14018961 0.14234359 0.14449503 0.14663648 0.14877236 0.15089947 0.15302471 0.155141 0.15725402 0.15935959 0.16145813 0.16355132 0.16563963 0.16772494 0.1698033 0.17187555 0.17394191 0.17600722 0.17806499 0.18011745 0.18216164 0.18420446 0.18624091 0.18827655 0.19030833 0.19233052 0.19434885 0.19636357 0.19837593 0.20037883 0.20238383 0.20438058 0.20637502 0.20836358 0.21034732 0.21232885 0.21430571 0.21627763 0.21824694 0.22021326 0.22217222 0.22412743 0.22608217 0.22803347 0.22998291 0.23192295 0.23385759 0.23579759 0.23772869 0.23965799 0.24157841 0.24349944 0.24541689 0.24733152 0.24924241 0.25115108 0.25305646 0.25495687 0.25685379 0.25874221 0.26063593 0.26252242 0.26440664 0.26628698 0.26816398 0.27004031 0.27191147 0.27377527 0.27564404 0.27750921 0.27935984 0.28121741 0.28306997 0.2849209 0.28676631 0.28860828 0.29045122 0.29229007 0.29412417 0.29595331 0.29778415 0.29960719 0.30142759 0.30324755 0.30506054 0.30687771 0.30869136 0.31049896 0.31230004 0.31410149 0.3159051 0.3177027 0.31949741 0.32128578 0.32306955 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +42 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03275873 0.00083377 0.02543348 0.0448834 0.0667768 0.07915202 0.09113854 0.10280435 0.11420819 0.12538567 0.13636556 0.14716567 0.15780447 0.1683014 0.178663 0.18889865 0.19901765 0.20902392 0.21892797 0.22873221 0.23844548 0.24806675 0.25759734 0.26705022 0.27641741 0.2857055 0.29491896 0.3040543 0.31311378 0.32210299 0.33103247 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/Test_Cases/5MW_NR_Baseline/DISCON.IN b/Test_Cases/5MW_NR_Baseline/DISCON.IN index 12916d09c..6d38f170e 100644 --- a/Test_Cases/5MW_NR_Baseline/DISCON.IN +++ b/Test_Cases/5MW_NR_Baseline/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the 5MW_Land wind turbine -! - File written using NREL Baseline Controller tuning logic on 10/01/19 +! - File written using NREL Baseline Controller tuning logic on 10/07/19 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file @@ -16,24 +16,24 @@ 1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} !------- FILTERS ---------------------------------------------------------- -1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +1.543417826848871 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] 0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] 0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] 0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.5 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [Hz]. !------- BLADE PITCH CONTROL ---------------------------------------------- -136 ! PC_GS_n - Amount of gain-scheduling table entries -0. 0.01843267 0.03012466 0.03938211 0.0473159 0.05438725 0.0608399 0.06682165 0.07243603 0.07774601 0.08280179 0.08764533 0.0922973 0.09678511 0.10113084 0.10534505 0.10944741 0.11344459 0.11734245 0.12115249 0.12488383 0.12853954 0.13212927 0.13565125 0.13911823 0.1425236 0.14587973 0.1491875 0.15244657 0.15566288 0.15883986 0.16197375 0.16506986 0.16813214 0.17115907 0.17415428 0.17711497 0.18004808 0.18295399 0.1858281 0.1886768 0.19150248 0.19430239 0.19707534 0.19983015 0.2025582 0.20526628 0.20795513 0.21062023 0.21326861 0.2158935 0.21850484 0.2210941 0.22366803 0.22622254 0.22876498 0.2312836 0.23379345 0.23628255 0.23875941 0.24122279 0.24366729 0.24610036 0.24852176 0.25092855 0.25332325 0.2557023 0.25807209 0.26042559 0.26276748 0.26510036 0.26742092 0.26973036 0.27202782 0.27431492 0.27658881 0.27885401 0.28110964 0.28336045 0.2855962 0.28782076 0.29003745 0.29224346 0.29444004 0.29663204 0.2988061 0.30097858 0.30314198 0.30529447 0.30743825 0.30958 0.31170708 0.31382687 0.31593631 0.3180419 0.32013786 0.32222978 0.32431029 0.32638663 0.32845309 0.33051357 0.33256802 0.33461455 0.33665611 0.33868284 0.34071023 0.34272963 0.34474196 0.34674528 0.34875073 0.35074041 0.35272695 0.35470654 0.35668277 0.35864961 0.36061312 0.36256798 0.36452117 0.36646633 0.36840178 0.37033735 0.3722649 0.37418622 0.37609996 0.37801477 0.37991806 0.38181864 0.38371323 0.38560453 0.38749153 0.38937202 0.39124103 0.39310673 0.39497577 0.39683082 0.39868511 ! PC_GS_angles - Gain-schedule table: pitch angles --0.02019147 -0.01950333 -0.01885443 -0.0182415 -0.01766165 -0.01711225 -0.01659098 -0.01609573 -0.01562459 -0.01517585 -0.01474794 -0.01433946 -0.0139491 -0.01357569 -0.01321814 -0.01287547 -0.01254676 -0.01223119 -0.01192797 -0.0116364 -0.01135581 -0.01108561 -0.01082521 -0.01057411 -0.0103318 -0.01009784 -0.00987181 -0.00965329 -0.00944194 -0.00923739 -0.00903933 -0.00884745 -0.00866147 -0.00848112 -0.00830614 -0.00813631 -0.0079714 -0.00781119 -0.00765549 -0.00750411 -0.00735688 -0.00721362 -0.00707417 -0.0069384 -0.00680614 -0.00667728 -0.00655167 -0.0064292 -0.00630975 -0.00619322 -0.00607949 -0.00596846 -0.00586005 -0.00575415 -0.00565069 -0.00554957 -0.00545073 -0.00535408 -0.00525955 -0.00516708 -0.00507659 -0.00498803 -0.00490133 -0.00481644 -0.00473329 -0.00465184 -0.00457204 -0.00449383 -0.00441716 -0.004342 -0.0042683 -0.00419602 -0.00412511 -0.00405553 -0.00398726 -0.00392025 -0.00385447 -0.00378988 -0.00372646 -0.00366417 -0.00360298 -0.00354286 -0.00348379 -0.00342574 -0.00336868 -0.00331258 -0.00325743 -0.00320319 -0.00314985 -0.00309739 -0.00304578 -0.002995 -0.00294503 -0.00289585 -0.00284745 -0.00279981 -0.0027529 -0.00270671 -0.00266123 -0.00261644 -0.00257232 -0.00252886 -0.00248604 -0.00244385 -0.00240228 -0.00236131 -0.00232093 -0.00228112 -0.00224188 -0.0022032 -0.00216505 -0.00212743 -0.00209033 -0.00205374 -0.00201765 -0.00198204 -0.00194691 -0.00191225 -0.00187805 -0.0018443 -0.00181099 -0.00177811 -0.00174566 -0.00171362 -0.00168199 -0.00165076 -0.00161992 -0.00158947 -0.00155939 -0.00152969 -0.00150035 -0.00147137 -0.00144274 -0.00141446 -0.00138651 -0.0013589 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains --0.00882307 -0.00856411 -0.00831992 -0.00808927 -0.00787106 -0.00766432 -0.00746816 -0.00728178 -0.00710449 -0.00693562 -0.0067746 -0.00662088 -0.00647398 -0.00633346 -0.00619891 -0.00606996 -0.00594626 -0.00582751 -0.0057134 -0.00560368 -0.00549809 -0.00539641 -0.00529842 -0.00520393 -0.00511274 -0.0050247 -0.00493964 -0.00485741 -0.00477787 -0.0047009 -0.00462637 -0.00455416 -0.00448417 -0.0044163 -0.00435046 -0.00428655 -0.00422449 -0.0041642 -0.00410561 -0.00404864 -0.00399324 -0.00393933 -0.00388685 -0.00383576 -0.00378599 -0.00373749 -0.00369023 -0.00364414 -0.00359919 -0.00355534 -0.00351254 -0.00347076 -0.00342996 -0.00339011 -0.00335117 -0.00331312 -0.00327593 -0.00323956 -0.00320399 -0.00316919 -0.00313514 -0.00310181 -0.00306918 -0.00303724 -0.00300595 -0.0029753 -0.00294526 -0.00291583 -0.00288698 -0.0028587 -0.00283096 -0.00280376 -0.00277708 -0.0027509 -0.0027252 -0.00269999 -0.00267523 -0.00265093 -0.00262706 -0.00260362 -0.00258059 -0.00255797 -0.00253574 -0.0025139 -0.00249242 -0.00247131 -0.00245056 -0.00243015 -0.00241008 -0.00239033 -0.00237091 -0.0023518 -0.002333 -0.00231449 -0.00229628 -0.00227835 -0.0022607 -0.00224332 -0.0022262 -0.00220935 -0.00219274 -0.00217639 -0.00216028 -0.0021444 -0.00212876 -0.00211334 -0.00209814 -0.00208316 -0.0020684 -0.00205384 -0.00203948 -0.00202533 -0.00201136 -0.00199759 -0.00198401 -0.00197061 -0.00195739 -0.00194435 -0.00193148 -0.00191878 -0.00190624 -0.00189387 -0.00188166 -0.0018696 -0.0018577 -0.00184595 -0.00183434 -0.00182288 -0.00181157 -0.00180039 -0.00178935 -0.00177844 -0.00176767 -0.00175702 -0.00174651 -0.00173612 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +27 ! PC_GS_n - Amount of gain-scheduling table entries +0.05852874 0.08586931 0.10789716 0.1271165 0.14453395 0.16067791 0.17585826 0.19027256 0.20405942 0.21730904 0.23010311 0.24249689 0.2545414 0.26626371 0.27770397 0.28889173 0.29983774 0.31057221 0.32109644 0.33144053 0.34160524 0.35160739 0.36145513 0.37115299 0.38071093 0.3901412 0.39943831 ! PC_GS_angles - Gain-schedule table: pitch angles +-0.01603382 -0.01396602 -0.01229584 -0.01091865 -0.00976358 -0.00878088 -0.00793467 -0.00719835 -0.00655181 -0.00597959 -0.00546956 -0.00501211 -0.00459951 -0.00422546 -0.00388481 -0.00357328 -0.00328728 -0.0030238 -0.00278028 -0.00255453 -0.00234468 -0.00214911 -0.0019664 -0.00179533 -0.00163481 -0.00148391 -0.00134179 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-0.00715561 -0.00639445 -0.00577965 -0.00527271 -0.00484752 -0.00448579 -0.0041743 -0.00390326 -0.00366527 -0.00345463 -0.00326689 -0.0030985 -0.00294662 -0.00280893 -0.00268354 -0.00256886 -0.00246359 -0.0023666 -0.00227696 -0.00219386 -0.00211661 -0.00204462 -0.00197737 -0.0019144 -0.00185531 -0.00179976 -0.00174745 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +122.90957658394467 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. 0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] 0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] @@ -41,63 +41,64 @@ 0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] -1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. -2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] +0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] !------- VS TORQUE CONTROL ------------------------------------------------ -0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] -43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +94.4 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +43093.55150917838 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +47402.906660096225 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. -91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] -2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] -5.0E+06 ! VS_RtPwr - Wind turbine rated power [W] -43093.55 ! VS_RtTq - Rated torque, [Nm]. -120.113 ! VS_RefSpd - Rated generator speed [rad/s] +0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5000000 ! VS_RtPwr - Wind turbine rated power [W] +43093.55150917838 ! VS_RtTq - Rated torque, [Nm]. +122.90957658394467 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-889.094048017944 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-172.0461874545648 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.4 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. !------- SETPOINT SMOOTHER --------------------------------------------- 30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. 0.0001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. !------- WIND SPEED ESTIMATOR --------------------------------------------- -63.0 ! WE_BladeRadius - Blade length [m] +63.0 ! WE_BladeRadius - Blade length [m] 4 ! WE_CP_n - Amount of parameters in the Cp array -14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function -20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] -97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +40469564.444 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1.225 ! WE_RhoAir - Air density, [kg m^-3] "../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) -320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -23 ! WE_FOPoles_N - Number of first-order system poles used in EKF -3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles +320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +42 ! WE_FOPoles_N - Number of first-order system poles used in EKF + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02665071 -0.02998205 -0.03331339 -0.03664473 -0.03997606 -0.0433074 -0.04663874 -0.04997008 -0.05330142 -0.05663276 -0.0599641 -0.06329543 -0.06662677 -0.06995811 -0.07328945 -0.06321278 -0.07469151 -0.08828579 -0.10297822 -0.11842623 -0.13448765 -0.15120764 -0.168455 -0.18635293 -0.20483641 -0.22395323 -0.24348262 -0.26365771 -0.2842596 -0.30535287 -0.32683352 -0.3487705 -0.37113879 -0.39376001 -0.41675049 -0.44017539 -0.46432564 -0.4888057 -0.51273708 -0.53554138 -0.55932133 -0.58645605 ! WE_FOPoles - First order system poles !------- YAW CONTROL ------------------------------------------------------ -1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] -0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) --0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp --0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki -0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. -1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. -0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad] -1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] -0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] -0.0034906 ! Y_Rate - Yaw rate [rad/s] +0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.0 ! Y_MErrSet - Yaw alignment error, set point [rad] +0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0 ! Y_Rate - Yaw rate [rad/s] !------- TOWER FORE-AFT DAMPING ------------------------------------------- -1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag -0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] -0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] +0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] !------- PEAK SHAVING ------------------------------------------- -210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) - 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.02962541 -0.02230897 -0.01548946 -0.00915689 -0.00323985 0.00231633 0.00755924 0.01252064 0.01723337 0.02171883 0.02600713 0.03010809 0.03403543 0.03780094 0.04141197 0.0448834 0.04301121 0.04572902 0.04841563 0.05107257 0.05370175 0.05630738 0.05888727 0.06144604 0.06398009 0.06649806 0.06899513 0.07147461 0.07393783 0.0763848 0.07881322 0.08122765 0.08363032 0.08601684 0.0883911 0.09075519 0.09310191 0.09543925 0.09776725 0.10008031 0.1023843 0.10467939 0.10696282 0.10923552 0.11150342 0.11375564 0.11600427 0.118243 0.12047296 0.12269376 0.12490488 0.12711415 0.12931036 0.13150096 0.13368154 0.13585982 0.13803009 0.14018961 0.14234359 0.14449503 0.14663648 0.14877236 0.15089947 0.15302471 0.155141 0.15725402 0.15935959 0.16145813 0.16355132 0.16563963 0.16772494 0.1698033 0.17187555 0.17394191 0.17600722 0.17806499 0.18011745 0.18216164 0.18420446 0.18624091 0.18827655 0.19030833 0.19233052 0.19434885 0.19636357 0.19837593 0.20037883 0.20238383 0.20438058 0.20637502 0.20836358 0.21034732 0.21232885 0.21430571 0.21627763 0.21824694 0.22021326 0.22217222 0.22412743 0.22608217 0.22803347 0.22998291 0.23192295 0.23385759 0.23579759 0.23772869 0.23965799 0.24157841 0.24349944 0.24541689 0.24733152 0.24924241 0.25115108 0.25305646 0.25495687 0.25685379 0.25874221 0.26063593 0.26252242 0.26440664 0.26628698 0.26816398 0.27004031 0.27191147 0.27377527 0.27564404 0.27750921 0.27935984 0.28121741 0.28306997 0.2849209 0.28676631 0.28860828 0.29045122 0.29229007 0.29412417 0.29595331 0.29778415 0.29960719 0.30142759 0.30324755 0.30506054 0.30687771 0.30869136 0.31049896 0.31230004 0.31410149 0.3159051 0.3177027 0.31949741 0.32128578 0.32306955 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +42 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03275873 0.00083377 0.02543348 0.0448834 0.0667768 0.07915202 0.09113854 0.10280435 0.11420819 0.12538567 0.13636556 0.14716567 0.15780447 0.1683014 0.178663 0.18889865 0.19901765 0.20902392 0.21892797 0.22873221 0.23844548 0.24806675 0.25759734 0.26705022 0.27641741 0.2857055 0.29491896 0.3040543 0.31311378 0.32210299 0.33103247 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/Test_Cases/5MW_OC4_AR_Baseline/DISCON.IN b/Test_Cases/5MW_OC4_AR_Baseline/DISCON.IN index 12916d09c..6d38f170e 100644 --- a/Test_Cases/5MW_OC4_AR_Baseline/DISCON.IN +++ b/Test_Cases/5MW_OC4_AR_Baseline/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the 5MW_Land wind turbine -! - File written using NREL Baseline Controller tuning logic on 10/01/19 +! - File written using NREL Baseline Controller tuning logic on 10/07/19 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file @@ -16,24 +16,24 @@ 1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} !------- FILTERS ---------------------------------------------------------- -1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +1.543417826848871 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] 0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] 0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] 0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.5 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [Hz]. !------- BLADE PITCH CONTROL ---------------------------------------------- -136 ! PC_GS_n - Amount of gain-scheduling table entries -0. 0.01843267 0.03012466 0.03938211 0.0473159 0.05438725 0.0608399 0.06682165 0.07243603 0.07774601 0.08280179 0.08764533 0.0922973 0.09678511 0.10113084 0.10534505 0.10944741 0.11344459 0.11734245 0.12115249 0.12488383 0.12853954 0.13212927 0.13565125 0.13911823 0.1425236 0.14587973 0.1491875 0.15244657 0.15566288 0.15883986 0.16197375 0.16506986 0.16813214 0.17115907 0.17415428 0.17711497 0.18004808 0.18295399 0.1858281 0.1886768 0.19150248 0.19430239 0.19707534 0.19983015 0.2025582 0.20526628 0.20795513 0.21062023 0.21326861 0.2158935 0.21850484 0.2210941 0.22366803 0.22622254 0.22876498 0.2312836 0.23379345 0.23628255 0.23875941 0.24122279 0.24366729 0.24610036 0.24852176 0.25092855 0.25332325 0.2557023 0.25807209 0.26042559 0.26276748 0.26510036 0.26742092 0.26973036 0.27202782 0.27431492 0.27658881 0.27885401 0.28110964 0.28336045 0.2855962 0.28782076 0.29003745 0.29224346 0.29444004 0.29663204 0.2988061 0.30097858 0.30314198 0.30529447 0.30743825 0.30958 0.31170708 0.31382687 0.31593631 0.3180419 0.32013786 0.32222978 0.32431029 0.32638663 0.32845309 0.33051357 0.33256802 0.33461455 0.33665611 0.33868284 0.34071023 0.34272963 0.34474196 0.34674528 0.34875073 0.35074041 0.35272695 0.35470654 0.35668277 0.35864961 0.36061312 0.36256798 0.36452117 0.36646633 0.36840178 0.37033735 0.3722649 0.37418622 0.37609996 0.37801477 0.37991806 0.38181864 0.38371323 0.38560453 0.38749153 0.38937202 0.39124103 0.39310673 0.39497577 0.39683082 0.39868511 ! PC_GS_angles - Gain-schedule table: pitch angles --0.02019147 -0.01950333 -0.01885443 -0.0182415 -0.01766165 -0.01711225 -0.01659098 -0.01609573 -0.01562459 -0.01517585 -0.01474794 -0.01433946 -0.0139491 -0.01357569 -0.01321814 -0.01287547 -0.01254676 -0.01223119 -0.01192797 -0.0116364 -0.01135581 -0.01108561 -0.01082521 -0.01057411 -0.0103318 -0.01009784 -0.00987181 -0.00965329 -0.00944194 -0.00923739 -0.00903933 -0.00884745 -0.00866147 -0.00848112 -0.00830614 -0.00813631 -0.0079714 -0.00781119 -0.00765549 -0.00750411 -0.00735688 -0.00721362 -0.00707417 -0.0069384 -0.00680614 -0.00667728 -0.00655167 -0.0064292 -0.00630975 -0.00619322 -0.00607949 -0.00596846 -0.00586005 -0.00575415 -0.00565069 -0.00554957 -0.00545073 -0.00535408 -0.00525955 -0.00516708 -0.00507659 -0.00498803 -0.00490133 -0.00481644 -0.00473329 -0.00465184 -0.00457204 -0.00449383 -0.00441716 -0.004342 -0.0042683 -0.00419602 -0.00412511 -0.00405553 -0.00398726 -0.00392025 -0.00385447 -0.00378988 -0.00372646 -0.00366417 -0.00360298 -0.00354286 -0.00348379 -0.00342574 -0.00336868 -0.00331258 -0.00325743 -0.00320319 -0.00314985 -0.00309739 -0.00304578 -0.002995 -0.00294503 -0.00289585 -0.00284745 -0.00279981 -0.0027529 -0.00270671 -0.00266123 -0.00261644 -0.00257232 -0.00252886 -0.00248604 -0.00244385 -0.00240228 -0.00236131 -0.00232093 -0.00228112 -0.00224188 -0.0022032 -0.00216505 -0.00212743 -0.00209033 -0.00205374 -0.00201765 -0.00198204 -0.00194691 -0.00191225 -0.00187805 -0.0018443 -0.00181099 -0.00177811 -0.00174566 -0.00171362 -0.00168199 -0.00165076 -0.00161992 -0.00158947 -0.00155939 -0.00152969 -0.00150035 -0.00147137 -0.00144274 -0.00141446 -0.00138651 -0.0013589 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains --0.00882307 -0.00856411 -0.00831992 -0.00808927 -0.00787106 -0.00766432 -0.00746816 -0.00728178 -0.00710449 -0.00693562 -0.0067746 -0.00662088 -0.00647398 -0.00633346 -0.00619891 -0.00606996 -0.00594626 -0.00582751 -0.0057134 -0.00560368 -0.00549809 -0.00539641 -0.00529842 -0.00520393 -0.00511274 -0.0050247 -0.00493964 -0.00485741 -0.00477787 -0.0047009 -0.00462637 -0.00455416 -0.00448417 -0.0044163 -0.00435046 -0.00428655 -0.00422449 -0.0041642 -0.00410561 -0.00404864 -0.00399324 -0.00393933 -0.00388685 -0.00383576 -0.00378599 -0.00373749 -0.00369023 -0.00364414 -0.00359919 -0.00355534 -0.00351254 -0.00347076 -0.00342996 -0.00339011 -0.00335117 -0.00331312 -0.00327593 -0.00323956 -0.00320399 -0.00316919 -0.00313514 -0.00310181 -0.00306918 -0.00303724 -0.00300595 -0.0029753 -0.00294526 -0.00291583 -0.00288698 -0.0028587 -0.00283096 -0.00280376 -0.00277708 -0.0027509 -0.0027252 -0.00269999 -0.00267523 -0.00265093 -0.00262706 -0.00260362 -0.00258059 -0.00255797 -0.00253574 -0.0025139 -0.00249242 -0.00247131 -0.00245056 -0.00243015 -0.00241008 -0.00239033 -0.00237091 -0.0023518 -0.002333 -0.00231449 -0.00229628 -0.00227835 -0.0022607 -0.00224332 -0.0022262 -0.00220935 -0.00219274 -0.00217639 -0.00216028 -0.0021444 -0.00212876 -0.00211334 -0.00209814 -0.00208316 -0.0020684 -0.00205384 -0.00203948 -0.00202533 -0.00201136 -0.00199759 -0.00198401 -0.00197061 -0.00195739 -0.00194435 -0.00193148 -0.00191878 -0.00190624 -0.00189387 -0.00188166 -0.0018696 -0.0018577 -0.00184595 -0.00183434 -0.00182288 -0.00181157 -0.00180039 -0.00178935 -0.00177844 -0.00176767 -0.00175702 -0.00174651 -0.00173612 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +27 ! PC_GS_n - Amount of gain-scheduling table entries +0.05852874 0.08586931 0.10789716 0.1271165 0.14453395 0.16067791 0.17585826 0.19027256 0.20405942 0.21730904 0.23010311 0.24249689 0.2545414 0.26626371 0.27770397 0.28889173 0.29983774 0.31057221 0.32109644 0.33144053 0.34160524 0.35160739 0.36145513 0.37115299 0.38071093 0.3901412 0.39943831 ! PC_GS_angles - Gain-schedule table: pitch angles +-0.01603382 -0.01396602 -0.01229584 -0.01091865 -0.00976358 -0.00878088 -0.00793467 -0.00719835 -0.00655181 -0.00597959 -0.00546956 -0.00501211 -0.00459951 -0.00422546 -0.00388481 -0.00357328 -0.00328728 -0.0030238 -0.00278028 -0.00255453 -0.00234468 -0.00214911 -0.0019664 -0.00179533 -0.00163481 -0.00148391 -0.00134179 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-0.00715561 -0.00639445 -0.00577965 -0.00527271 -0.00484752 -0.00448579 -0.0041743 -0.00390326 -0.00366527 -0.00345463 -0.00326689 -0.0030985 -0.00294662 -0.00280893 -0.00268354 -0.00256886 -0.00246359 -0.0023666 -0.00227696 -0.00219386 -0.00211661 -0.00204462 -0.00197737 -0.0019144 -0.00185531 -0.00179976 -0.00174745 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +122.90957658394467 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. 0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] 0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] @@ -41,63 +41,64 @@ 0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] -1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. -2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] +0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] !------- VS TORQUE CONTROL ------------------------------------------------ -0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] -43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +94.4 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +43093.55150917838 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +47402.906660096225 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. -91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] -2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] -5.0E+06 ! VS_RtPwr - Wind turbine rated power [W] -43093.55 ! VS_RtTq - Rated torque, [Nm]. -120.113 ! VS_RefSpd - Rated generator speed [rad/s] +0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5000000 ! VS_RtPwr - Wind turbine rated power [W] +43093.55150917838 ! VS_RtTq - Rated torque, [Nm]. +122.90957658394467 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-889.094048017944 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-172.0461874545648 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.4 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. !------- SETPOINT SMOOTHER --------------------------------------------- 30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. 0.0001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. !------- WIND SPEED ESTIMATOR --------------------------------------------- -63.0 ! WE_BladeRadius - Blade length [m] +63.0 ! WE_BladeRadius - Blade length [m] 4 ! WE_CP_n - Amount of parameters in the Cp array -14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function -20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] -97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +40469564.444 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1.225 ! WE_RhoAir - Air density, [kg m^-3] "../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) -320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -23 ! WE_FOPoles_N - Number of first-order system poles used in EKF -3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles +320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +42 ! WE_FOPoles_N - Number of first-order system poles used in EKF + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02665071 -0.02998205 -0.03331339 -0.03664473 -0.03997606 -0.0433074 -0.04663874 -0.04997008 -0.05330142 -0.05663276 -0.0599641 -0.06329543 -0.06662677 -0.06995811 -0.07328945 -0.06321278 -0.07469151 -0.08828579 -0.10297822 -0.11842623 -0.13448765 -0.15120764 -0.168455 -0.18635293 -0.20483641 -0.22395323 -0.24348262 -0.26365771 -0.2842596 -0.30535287 -0.32683352 -0.3487705 -0.37113879 -0.39376001 -0.41675049 -0.44017539 -0.46432564 -0.4888057 -0.51273708 -0.53554138 -0.55932133 -0.58645605 ! WE_FOPoles - First order system poles !------- YAW CONTROL ------------------------------------------------------ -1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] -0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) --0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp --0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki -0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. -1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. -0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad] -1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] -0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] -0.0034906 ! Y_Rate - Yaw rate [rad/s] +0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.0 ! Y_MErrSet - Yaw alignment error, set point [rad] +0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0 ! Y_Rate - Yaw rate [rad/s] !------- TOWER FORE-AFT DAMPING ------------------------------------------- -1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag -0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] -0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] +0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] !------- PEAK SHAVING ------------------------------------------- -210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) - 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.02962541 -0.02230897 -0.01548946 -0.00915689 -0.00323985 0.00231633 0.00755924 0.01252064 0.01723337 0.02171883 0.02600713 0.03010809 0.03403543 0.03780094 0.04141197 0.0448834 0.04301121 0.04572902 0.04841563 0.05107257 0.05370175 0.05630738 0.05888727 0.06144604 0.06398009 0.06649806 0.06899513 0.07147461 0.07393783 0.0763848 0.07881322 0.08122765 0.08363032 0.08601684 0.0883911 0.09075519 0.09310191 0.09543925 0.09776725 0.10008031 0.1023843 0.10467939 0.10696282 0.10923552 0.11150342 0.11375564 0.11600427 0.118243 0.12047296 0.12269376 0.12490488 0.12711415 0.12931036 0.13150096 0.13368154 0.13585982 0.13803009 0.14018961 0.14234359 0.14449503 0.14663648 0.14877236 0.15089947 0.15302471 0.155141 0.15725402 0.15935959 0.16145813 0.16355132 0.16563963 0.16772494 0.1698033 0.17187555 0.17394191 0.17600722 0.17806499 0.18011745 0.18216164 0.18420446 0.18624091 0.18827655 0.19030833 0.19233052 0.19434885 0.19636357 0.19837593 0.20037883 0.20238383 0.20438058 0.20637502 0.20836358 0.21034732 0.21232885 0.21430571 0.21627763 0.21824694 0.22021326 0.22217222 0.22412743 0.22608217 0.22803347 0.22998291 0.23192295 0.23385759 0.23579759 0.23772869 0.23965799 0.24157841 0.24349944 0.24541689 0.24733152 0.24924241 0.25115108 0.25305646 0.25495687 0.25685379 0.25874221 0.26063593 0.26252242 0.26440664 0.26628698 0.26816398 0.27004031 0.27191147 0.27377527 0.27564404 0.27750921 0.27935984 0.28121741 0.28306997 0.2849209 0.28676631 0.28860828 0.29045122 0.29229007 0.29412417 0.29595331 0.29778415 0.29960719 0.30142759 0.30324755 0.30506054 0.30687771 0.30869136 0.31049896 0.31230004 0.31410149 0.3159051 0.3177027 0.31949741 0.32128578 0.32306955 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +42 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03275873 0.00083377 0.02543348 0.0448834 0.0667768 0.07915202 0.09113854 0.10280435 0.11420819 0.12538567 0.13636556 0.14716567 0.15780447 0.1683014 0.178663 0.18889865 0.19901765 0.20902392 0.21892797 0.22873221 0.23844548 0.24806675 0.25759734 0.26705022 0.27641741 0.2857055 0.29491896 0.3040543 0.31311378 0.32210299 0.33103247 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/Test_Cases/5MW_OC4_ARsteady_Baseline/DISCON.IN b/Test_Cases/5MW_OC4_ARsteady_Baseline/DISCON.IN index 12916d09c..6d38f170e 100644 --- a/Test_Cases/5MW_OC4_ARsteady_Baseline/DISCON.IN +++ b/Test_Cases/5MW_OC4_ARsteady_Baseline/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the 5MW_Land wind turbine -! - File written using NREL Baseline Controller tuning logic on 10/01/19 +! - File written using NREL Baseline Controller tuning logic on 10/07/19 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file @@ -16,24 +16,24 @@ 1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} !------- FILTERS ---------------------------------------------------------- -1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +1.543417826848871 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] 0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] 0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] 0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.5 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [Hz]. !------- BLADE PITCH CONTROL ---------------------------------------------- -136 ! PC_GS_n - Amount of gain-scheduling table entries -0. 0.01843267 0.03012466 0.03938211 0.0473159 0.05438725 0.0608399 0.06682165 0.07243603 0.07774601 0.08280179 0.08764533 0.0922973 0.09678511 0.10113084 0.10534505 0.10944741 0.11344459 0.11734245 0.12115249 0.12488383 0.12853954 0.13212927 0.13565125 0.13911823 0.1425236 0.14587973 0.1491875 0.15244657 0.15566288 0.15883986 0.16197375 0.16506986 0.16813214 0.17115907 0.17415428 0.17711497 0.18004808 0.18295399 0.1858281 0.1886768 0.19150248 0.19430239 0.19707534 0.19983015 0.2025582 0.20526628 0.20795513 0.21062023 0.21326861 0.2158935 0.21850484 0.2210941 0.22366803 0.22622254 0.22876498 0.2312836 0.23379345 0.23628255 0.23875941 0.24122279 0.24366729 0.24610036 0.24852176 0.25092855 0.25332325 0.2557023 0.25807209 0.26042559 0.26276748 0.26510036 0.26742092 0.26973036 0.27202782 0.27431492 0.27658881 0.27885401 0.28110964 0.28336045 0.2855962 0.28782076 0.29003745 0.29224346 0.29444004 0.29663204 0.2988061 0.30097858 0.30314198 0.30529447 0.30743825 0.30958 0.31170708 0.31382687 0.31593631 0.3180419 0.32013786 0.32222978 0.32431029 0.32638663 0.32845309 0.33051357 0.33256802 0.33461455 0.33665611 0.33868284 0.34071023 0.34272963 0.34474196 0.34674528 0.34875073 0.35074041 0.35272695 0.35470654 0.35668277 0.35864961 0.36061312 0.36256798 0.36452117 0.36646633 0.36840178 0.37033735 0.3722649 0.37418622 0.37609996 0.37801477 0.37991806 0.38181864 0.38371323 0.38560453 0.38749153 0.38937202 0.39124103 0.39310673 0.39497577 0.39683082 0.39868511 ! PC_GS_angles - Gain-schedule table: pitch angles --0.02019147 -0.01950333 -0.01885443 -0.0182415 -0.01766165 -0.01711225 -0.01659098 -0.01609573 -0.01562459 -0.01517585 -0.01474794 -0.01433946 -0.0139491 -0.01357569 -0.01321814 -0.01287547 -0.01254676 -0.01223119 -0.01192797 -0.0116364 -0.01135581 -0.01108561 -0.01082521 -0.01057411 -0.0103318 -0.01009784 -0.00987181 -0.00965329 -0.00944194 -0.00923739 -0.00903933 -0.00884745 -0.00866147 -0.00848112 -0.00830614 -0.00813631 -0.0079714 -0.00781119 -0.00765549 -0.00750411 -0.00735688 -0.00721362 -0.00707417 -0.0069384 -0.00680614 -0.00667728 -0.00655167 -0.0064292 -0.00630975 -0.00619322 -0.00607949 -0.00596846 -0.00586005 -0.00575415 -0.00565069 -0.00554957 -0.00545073 -0.00535408 -0.00525955 -0.00516708 -0.00507659 -0.00498803 -0.00490133 -0.00481644 -0.00473329 -0.00465184 -0.00457204 -0.00449383 -0.00441716 -0.004342 -0.0042683 -0.00419602 -0.00412511 -0.00405553 -0.00398726 -0.00392025 -0.00385447 -0.00378988 -0.00372646 -0.00366417 -0.00360298 -0.00354286 -0.00348379 -0.00342574 -0.00336868 -0.00331258 -0.00325743 -0.00320319 -0.00314985 -0.00309739 -0.00304578 -0.002995 -0.00294503 -0.00289585 -0.00284745 -0.00279981 -0.0027529 -0.00270671 -0.00266123 -0.00261644 -0.00257232 -0.00252886 -0.00248604 -0.00244385 -0.00240228 -0.00236131 -0.00232093 -0.00228112 -0.00224188 -0.0022032 -0.00216505 -0.00212743 -0.00209033 -0.00205374 -0.00201765 -0.00198204 -0.00194691 -0.00191225 -0.00187805 -0.0018443 -0.00181099 -0.00177811 -0.00174566 -0.00171362 -0.00168199 -0.00165076 -0.00161992 -0.00158947 -0.00155939 -0.00152969 -0.00150035 -0.00147137 -0.00144274 -0.00141446 -0.00138651 -0.0013589 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains --0.00882307 -0.00856411 -0.00831992 -0.00808927 -0.00787106 -0.00766432 -0.00746816 -0.00728178 -0.00710449 -0.00693562 -0.0067746 -0.00662088 -0.00647398 -0.00633346 -0.00619891 -0.00606996 -0.00594626 -0.00582751 -0.0057134 -0.00560368 -0.00549809 -0.00539641 -0.00529842 -0.00520393 -0.00511274 -0.0050247 -0.00493964 -0.00485741 -0.00477787 -0.0047009 -0.00462637 -0.00455416 -0.00448417 -0.0044163 -0.00435046 -0.00428655 -0.00422449 -0.0041642 -0.00410561 -0.00404864 -0.00399324 -0.00393933 -0.00388685 -0.00383576 -0.00378599 -0.00373749 -0.00369023 -0.00364414 -0.00359919 -0.00355534 -0.00351254 -0.00347076 -0.00342996 -0.00339011 -0.00335117 -0.00331312 -0.00327593 -0.00323956 -0.00320399 -0.00316919 -0.00313514 -0.00310181 -0.00306918 -0.00303724 -0.00300595 -0.0029753 -0.00294526 -0.00291583 -0.00288698 -0.0028587 -0.00283096 -0.00280376 -0.00277708 -0.0027509 -0.0027252 -0.00269999 -0.00267523 -0.00265093 -0.00262706 -0.00260362 -0.00258059 -0.00255797 -0.00253574 -0.0025139 -0.00249242 -0.00247131 -0.00245056 -0.00243015 -0.00241008 -0.00239033 -0.00237091 -0.0023518 -0.002333 -0.00231449 -0.00229628 -0.00227835 -0.0022607 -0.00224332 -0.0022262 -0.00220935 -0.00219274 -0.00217639 -0.00216028 -0.0021444 -0.00212876 -0.00211334 -0.00209814 -0.00208316 -0.0020684 -0.00205384 -0.00203948 -0.00202533 -0.00201136 -0.00199759 -0.00198401 -0.00197061 -0.00195739 -0.00194435 -0.00193148 -0.00191878 -0.00190624 -0.00189387 -0.00188166 -0.0018696 -0.0018577 -0.00184595 -0.00183434 -0.00182288 -0.00181157 -0.00180039 -0.00178935 -0.00177844 -0.00176767 -0.00175702 -0.00174651 -0.00173612 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +27 ! PC_GS_n - Amount of gain-scheduling table entries +0.05852874 0.08586931 0.10789716 0.1271165 0.14453395 0.16067791 0.17585826 0.19027256 0.20405942 0.21730904 0.23010311 0.24249689 0.2545414 0.26626371 0.27770397 0.28889173 0.29983774 0.31057221 0.32109644 0.33144053 0.34160524 0.35160739 0.36145513 0.37115299 0.38071093 0.3901412 0.39943831 ! PC_GS_angles - Gain-schedule table: pitch angles +-0.01603382 -0.01396602 -0.01229584 -0.01091865 -0.00976358 -0.00878088 -0.00793467 -0.00719835 -0.00655181 -0.00597959 -0.00546956 -0.00501211 -0.00459951 -0.00422546 -0.00388481 -0.00357328 -0.00328728 -0.0030238 -0.00278028 -0.00255453 -0.00234468 -0.00214911 -0.0019664 -0.00179533 -0.00163481 -0.00148391 -0.00134179 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-0.00715561 -0.00639445 -0.00577965 -0.00527271 -0.00484752 -0.00448579 -0.0041743 -0.00390326 -0.00366527 -0.00345463 -0.00326689 -0.0030985 -0.00294662 -0.00280893 -0.00268354 -0.00256886 -0.00246359 -0.0023666 -0.00227696 -0.00219386 -0.00211661 -0.00204462 -0.00197737 -0.0019144 -0.00185531 -0.00179976 -0.00174745 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +122.90957658394467 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. 0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] 0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] @@ -41,63 +41,64 @@ 0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] -1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. -2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] +0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] !------- VS TORQUE CONTROL ------------------------------------------------ -0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] -43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +94.4 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +43093.55150917838 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +47402.906660096225 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. -91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] -2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] -5.0E+06 ! VS_RtPwr - Wind turbine rated power [W] -43093.55 ! VS_RtTq - Rated torque, [Nm]. -120.113 ! VS_RefSpd - Rated generator speed [rad/s] +0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5000000 ! VS_RtPwr - Wind turbine rated power [W] +43093.55150917838 ! VS_RtTq - Rated torque, [Nm]. +122.90957658394467 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-889.094048017944 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-172.0461874545648 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.4 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. !------- SETPOINT SMOOTHER --------------------------------------------- 30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. 0.0001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. !------- WIND SPEED ESTIMATOR --------------------------------------------- -63.0 ! WE_BladeRadius - Blade length [m] +63.0 ! WE_BladeRadius - Blade length [m] 4 ! WE_CP_n - Amount of parameters in the Cp array -14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function -20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] -97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +40469564.444 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1.225 ! WE_RhoAir - Air density, [kg m^-3] "../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) -320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -23 ! WE_FOPoles_N - Number of first-order system poles used in EKF -3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles +320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +42 ! WE_FOPoles_N - Number of first-order system poles used in EKF + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02665071 -0.02998205 -0.03331339 -0.03664473 -0.03997606 -0.0433074 -0.04663874 -0.04997008 -0.05330142 -0.05663276 -0.0599641 -0.06329543 -0.06662677 -0.06995811 -0.07328945 -0.06321278 -0.07469151 -0.08828579 -0.10297822 -0.11842623 -0.13448765 -0.15120764 -0.168455 -0.18635293 -0.20483641 -0.22395323 -0.24348262 -0.26365771 -0.2842596 -0.30535287 -0.32683352 -0.3487705 -0.37113879 -0.39376001 -0.41675049 -0.44017539 -0.46432564 -0.4888057 -0.51273708 -0.53554138 -0.55932133 -0.58645605 ! WE_FOPoles - First order system poles !------- YAW CONTROL ------------------------------------------------------ -1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] -0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) --0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp --0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki -0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. -1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. -0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad] -1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] -0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] -0.0034906 ! Y_Rate - Yaw rate [rad/s] +0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.0 ! Y_MErrSet - Yaw alignment error, set point [rad] +0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0 ! Y_Rate - Yaw rate [rad/s] !------- TOWER FORE-AFT DAMPING ------------------------------------------- -1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag -0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] -0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] +0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] !------- PEAK SHAVING ------------------------------------------- -210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) - 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.02962541 -0.02230897 -0.01548946 -0.00915689 -0.00323985 0.00231633 0.00755924 0.01252064 0.01723337 0.02171883 0.02600713 0.03010809 0.03403543 0.03780094 0.04141197 0.0448834 0.04301121 0.04572902 0.04841563 0.05107257 0.05370175 0.05630738 0.05888727 0.06144604 0.06398009 0.06649806 0.06899513 0.07147461 0.07393783 0.0763848 0.07881322 0.08122765 0.08363032 0.08601684 0.0883911 0.09075519 0.09310191 0.09543925 0.09776725 0.10008031 0.1023843 0.10467939 0.10696282 0.10923552 0.11150342 0.11375564 0.11600427 0.118243 0.12047296 0.12269376 0.12490488 0.12711415 0.12931036 0.13150096 0.13368154 0.13585982 0.13803009 0.14018961 0.14234359 0.14449503 0.14663648 0.14877236 0.15089947 0.15302471 0.155141 0.15725402 0.15935959 0.16145813 0.16355132 0.16563963 0.16772494 0.1698033 0.17187555 0.17394191 0.17600722 0.17806499 0.18011745 0.18216164 0.18420446 0.18624091 0.18827655 0.19030833 0.19233052 0.19434885 0.19636357 0.19837593 0.20037883 0.20238383 0.20438058 0.20637502 0.20836358 0.21034732 0.21232885 0.21430571 0.21627763 0.21824694 0.22021326 0.22217222 0.22412743 0.22608217 0.22803347 0.22998291 0.23192295 0.23385759 0.23579759 0.23772869 0.23965799 0.24157841 0.24349944 0.24541689 0.24733152 0.24924241 0.25115108 0.25305646 0.25495687 0.25685379 0.25874221 0.26063593 0.26252242 0.26440664 0.26628698 0.26816398 0.27004031 0.27191147 0.27377527 0.27564404 0.27750921 0.27935984 0.28121741 0.28306997 0.2849209 0.28676631 0.28860828 0.29045122 0.29229007 0.29412417 0.29595331 0.29778415 0.29960719 0.30142759 0.30324755 0.30506054 0.30687771 0.30869136 0.31049896 0.31230004 0.31410149 0.3159051 0.3177027 0.31949741 0.32128578 0.32306955 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +42 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03275873 0.00083377 0.02543348 0.0448834 0.0667768 0.07915202 0.09113854 0.10280435 0.11420819 0.12538567 0.13636556 0.14716567 0.15780447 0.1683014 0.178663 0.18889865 0.19901765 0.20902392 0.21892797 0.22873221 0.23844548 0.24806675 0.25759734 0.26705022 0.27641741 0.2857055 0.29491896 0.3040543 0.31311378 0.32210299 0.33103247 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/Test_Cases/5MW_OC4_ARsteady_Legacy/NRELOffshrBsline5MW_OC4DeepCwindSemi_ServoDyn.dat b/Test_Cases/5MW_OC4_ARsteady_Legacy/NRELOffshrBsline5MW_OC4DeepCwindSemi_ServoDyn.dat index cf8909fc0..26d16dbeb 100644 --- a/Test_Cases/5MW_OC4_ARsteady_Legacy/NRELOffshrBsline5MW_OC4DeepCwindSemi_ServoDyn.dat +++ b/Test_Cases/5MW_OC4_ARsteady_Legacy/NRELOffshrBsline5MW_OC4DeepCwindSemi_ServoDyn.dat @@ -63,7 +63,7 @@ False CompNTMD - Compute nacelle tuned mass damper {true/false} (fla False CompTTMD - Compute tower tuned mass damper {true/false} (flag) "unused" TTMDfile - Name of the file for tower tuned mass damper (quoted string) [unused when CompTTMD is false] ---------------------- BLADED INTERFACE ---------------------------------------- [used only with Bladed Interface] -"../5MW_Baseline/DISCON/DISCON_OC3Hywind.dll" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] +"../5MW_Baseline/DISCON/DISCON.dll" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] "DISCON.IN" DLL_InFile - Name of input file sent to the DLL (-) [used only with Bladed Interface] "DISCON" DLL_ProcName - Name of procedure in DLL to be called (-) [case sensitive; used only with DLL Interface] "default" DLL_DT - Communication interval for dynamic library (s) (or "default") [used only with Bladed Interface] diff --git a/Test_Cases/5MW_OC4_MH_Baseline/DISCON.IN b/Test_Cases/5MW_OC4_MH_Baseline/DISCON.IN index 12916d09c..6d38f170e 100644 --- a/Test_Cases/5MW_OC4_MH_Baseline/DISCON.IN +++ b/Test_Cases/5MW_OC4_MH_Baseline/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the 5MW_Land wind turbine -! - File written using NREL Baseline Controller tuning logic on 10/01/19 +! - File written using NREL Baseline Controller tuning logic on 10/07/19 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file @@ -16,24 +16,24 @@ 1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} !------- FILTERS ---------------------------------------------------------- -1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +1.543417826848871 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] 0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] 0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] 0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.5 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [Hz]. !------- BLADE PITCH CONTROL ---------------------------------------------- -136 ! PC_GS_n - Amount of gain-scheduling table entries -0. 0.01843267 0.03012466 0.03938211 0.0473159 0.05438725 0.0608399 0.06682165 0.07243603 0.07774601 0.08280179 0.08764533 0.0922973 0.09678511 0.10113084 0.10534505 0.10944741 0.11344459 0.11734245 0.12115249 0.12488383 0.12853954 0.13212927 0.13565125 0.13911823 0.1425236 0.14587973 0.1491875 0.15244657 0.15566288 0.15883986 0.16197375 0.16506986 0.16813214 0.17115907 0.17415428 0.17711497 0.18004808 0.18295399 0.1858281 0.1886768 0.19150248 0.19430239 0.19707534 0.19983015 0.2025582 0.20526628 0.20795513 0.21062023 0.21326861 0.2158935 0.21850484 0.2210941 0.22366803 0.22622254 0.22876498 0.2312836 0.23379345 0.23628255 0.23875941 0.24122279 0.24366729 0.24610036 0.24852176 0.25092855 0.25332325 0.2557023 0.25807209 0.26042559 0.26276748 0.26510036 0.26742092 0.26973036 0.27202782 0.27431492 0.27658881 0.27885401 0.28110964 0.28336045 0.2855962 0.28782076 0.29003745 0.29224346 0.29444004 0.29663204 0.2988061 0.30097858 0.30314198 0.30529447 0.30743825 0.30958 0.31170708 0.31382687 0.31593631 0.3180419 0.32013786 0.32222978 0.32431029 0.32638663 0.32845309 0.33051357 0.33256802 0.33461455 0.33665611 0.33868284 0.34071023 0.34272963 0.34474196 0.34674528 0.34875073 0.35074041 0.35272695 0.35470654 0.35668277 0.35864961 0.36061312 0.36256798 0.36452117 0.36646633 0.36840178 0.37033735 0.3722649 0.37418622 0.37609996 0.37801477 0.37991806 0.38181864 0.38371323 0.38560453 0.38749153 0.38937202 0.39124103 0.39310673 0.39497577 0.39683082 0.39868511 ! PC_GS_angles - Gain-schedule table: pitch angles --0.02019147 -0.01950333 -0.01885443 -0.0182415 -0.01766165 -0.01711225 -0.01659098 -0.01609573 -0.01562459 -0.01517585 -0.01474794 -0.01433946 -0.0139491 -0.01357569 -0.01321814 -0.01287547 -0.01254676 -0.01223119 -0.01192797 -0.0116364 -0.01135581 -0.01108561 -0.01082521 -0.01057411 -0.0103318 -0.01009784 -0.00987181 -0.00965329 -0.00944194 -0.00923739 -0.00903933 -0.00884745 -0.00866147 -0.00848112 -0.00830614 -0.00813631 -0.0079714 -0.00781119 -0.00765549 -0.00750411 -0.00735688 -0.00721362 -0.00707417 -0.0069384 -0.00680614 -0.00667728 -0.00655167 -0.0064292 -0.00630975 -0.00619322 -0.00607949 -0.00596846 -0.00586005 -0.00575415 -0.00565069 -0.00554957 -0.00545073 -0.00535408 -0.00525955 -0.00516708 -0.00507659 -0.00498803 -0.00490133 -0.00481644 -0.00473329 -0.00465184 -0.00457204 -0.00449383 -0.00441716 -0.004342 -0.0042683 -0.00419602 -0.00412511 -0.00405553 -0.00398726 -0.00392025 -0.00385447 -0.00378988 -0.00372646 -0.00366417 -0.00360298 -0.00354286 -0.00348379 -0.00342574 -0.00336868 -0.00331258 -0.00325743 -0.00320319 -0.00314985 -0.00309739 -0.00304578 -0.002995 -0.00294503 -0.00289585 -0.00284745 -0.00279981 -0.0027529 -0.00270671 -0.00266123 -0.00261644 -0.00257232 -0.00252886 -0.00248604 -0.00244385 -0.00240228 -0.00236131 -0.00232093 -0.00228112 -0.00224188 -0.0022032 -0.00216505 -0.00212743 -0.00209033 -0.00205374 -0.00201765 -0.00198204 -0.00194691 -0.00191225 -0.00187805 -0.0018443 -0.00181099 -0.00177811 -0.00174566 -0.00171362 -0.00168199 -0.00165076 -0.00161992 -0.00158947 -0.00155939 -0.00152969 -0.00150035 -0.00147137 -0.00144274 -0.00141446 -0.00138651 -0.0013589 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains --0.00882307 -0.00856411 -0.00831992 -0.00808927 -0.00787106 -0.00766432 -0.00746816 -0.00728178 -0.00710449 -0.00693562 -0.0067746 -0.00662088 -0.00647398 -0.00633346 -0.00619891 -0.00606996 -0.00594626 -0.00582751 -0.0057134 -0.00560368 -0.00549809 -0.00539641 -0.00529842 -0.00520393 -0.00511274 -0.0050247 -0.00493964 -0.00485741 -0.00477787 -0.0047009 -0.00462637 -0.00455416 -0.00448417 -0.0044163 -0.00435046 -0.00428655 -0.00422449 -0.0041642 -0.00410561 -0.00404864 -0.00399324 -0.00393933 -0.00388685 -0.00383576 -0.00378599 -0.00373749 -0.00369023 -0.00364414 -0.00359919 -0.00355534 -0.00351254 -0.00347076 -0.00342996 -0.00339011 -0.00335117 -0.00331312 -0.00327593 -0.00323956 -0.00320399 -0.00316919 -0.00313514 -0.00310181 -0.00306918 -0.00303724 -0.00300595 -0.0029753 -0.00294526 -0.00291583 -0.00288698 -0.0028587 -0.00283096 -0.00280376 -0.00277708 -0.0027509 -0.0027252 -0.00269999 -0.00267523 -0.00265093 -0.00262706 -0.00260362 -0.00258059 -0.00255797 -0.00253574 -0.0025139 -0.00249242 -0.00247131 -0.00245056 -0.00243015 -0.00241008 -0.00239033 -0.00237091 -0.0023518 -0.002333 -0.00231449 -0.00229628 -0.00227835 -0.0022607 -0.00224332 -0.0022262 -0.00220935 -0.00219274 -0.00217639 -0.00216028 -0.0021444 -0.00212876 -0.00211334 -0.00209814 -0.00208316 -0.0020684 -0.00205384 -0.00203948 -0.00202533 -0.00201136 -0.00199759 -0.00198401 -0.00197061 -0.00195739 -0.00194435 -0.00193148 -0.00191878 -0.00190624 -0.00189387 -0.00188166 -0.0018696 -0.0018577 -0.00184595 -0.00183434 -0.00182288 -0.00181157 -0.00180039 -0.00178935 -0.00177844 -0.00176767 -0.00175702 -0.00174651 -0.00173612 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +27 ! PC_GS_n - Amount of gain-scheduling table entries +0.05852874 0.08586931 0.10789716 0.1271165 0.14453395 0.16067791 0.17585826 0.19027256 0.20405942 0.21730904 0.23010311 0.24249689 0.2545414 0.26626371 0.27770397 0.28889173 0.29983774 0.31057221 0.32109644 0.33144053 0.34160524 0.35160739 0.36145513 0.37115299 0.38071093 0.3901412 0.39943831 ! PC_GS_angles - Gain-schedule table: pitch angles +-0.01603382 -0.01396602 -0.01229584 -0.01091865 -0.00976358 -0.00878088 -0.00793467 -0.00719835 -0.00655181 -0.00597959 -0.00546956 -0.00501211 -0.00459951 -0.00422546 -0.00388481 -0.00357328 -0.00328728 -0.0030238 -0.00278028 -0.00255453 -0.00234468 -0.00214911 -0.0019664 -0.00179533 -0.00163481 -0.00148391 -0.00134179 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-0.00715561 -0.00639445 -0.00577965 -0.00527271 -0.00484752 -0.00448579 -0.0041743 -0.00390326 -0.00366527 -0.00345463 -0.00326689 -0.0030985 -0.00294662 -0.00280893 -0.00268354 -0.00256886 -0.00246359 -0.0023666 -0.00227696 -0.00219386 -0.00211661 -0.00204462 -0.00197737 -0.0019144 -0.00185531 -0.00179976 -0.00174745 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +122.90957658394467 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. 0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] 0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] @@ -41,63 +41,64 @@ 0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] -1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. -2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] +0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] !------- VS TORQUE CONTROL ------------------------------------------------ -0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] -43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +94.4 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +43093.55150917838 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +47402.906660096225 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. -91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] -2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] -5.0E+06 ! VS_RtPwr - Wind turbine rated power [W] -43093.55 ! VS_RtTq - Rated torque, [Nm]. -120.113 ! VS_RefSpd - Rated generator speed [rad/s] +0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5000000 ! VS_RtPwr - Wind turbine rated power [W] +43093.55150917838 ! VS_RtTq - Rated torque, [Nm]. +122.90957658394467 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-889.094048017944 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-172.0461874545648 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.4 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. !------- SETPOINT SMOOTHER --------------------------------------------- 30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. 0.0001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. !------- WIND SPEED ESTIMATOR --------------------------------------------- -63.0 ! WE_BladeRadius - Blade length [m] +63.0 ! WE_BladeRadius - Blade length [m] 4 ! WE_CP_n - Amount of parameters in the Cp array -14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function -20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] -97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +40469564.444 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1.225 ! WE_RhoAir - Air density, [kg m^-3] "../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) -320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -23 ! WE_FOPoles_N - Number of first-order system poles used in EKF -3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles +320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +42 ! WE_FOPoles_N - Number of first-order system poles used in EKF + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02665071 -0.02998205 -0.03331339 -0.03664473 -0.03997606 -0.0433074 -0.04663874 -0.04997008 -0.05330142 -0.05663276 -0.0599641 -0.06329543 -0.06662677 -0.06995811 -0.07328945 -0.06321278 -0.07469151 -0.08828579 -0.10297822 -0.11842623 -0.13448765 -0.15120764 -0.168455 -0.18635293 -0.20483641 -0.22395323 -0.24348262 -0.26365771 -0.2842596 -0.30535287 -0.32683352 -0.3487705 -0.37113879 -0.39376001 -0.41675049 -0.44017539 -0.46432564 -0.4888057 -0.51273708 -0.53554138 -0.55932133 -0.58645605 ! WE_FOPoles - First order system poles !------- YAW CONTROL ------------------------------------------------------ -1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] -0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) --0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp --0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki -0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. -1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. -0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad] -1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] -0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] -0.0034906 ! Y_Rate - Yaw rate [rad/s] +0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.0 ! Y_MErrSet - Yaw alignment error, set point [rad] +0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0 ! Y_Rate - Yaw rate [rad/s] !------- TOWER FORE-AFT DAMPING ------------------------------------------- -1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag -0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] -0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] +0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] !------- PEAK SHAVING ------------------------------------------- -210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) - 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.02962541 -0.02230897 -0.01548946 -0.00915689 -0.00323985 0.00231633 0.00755924 0.01252064 0.01723337 0.02171883 0.02600713 0.03010809 0.03403543 0.03780094 0.04141197 0.0448834 0.04301121 0.04572902 0.04841563 0.05107257 0.05370175 0.05630738 0.05888727 0.06144604 0.06398009 0.06649806 0.06899513 0.07147461 0.07393783 0.0763848 0.07881322 0.08122765 0.08363032 0.08601684 0.0883911 0.09075519 0.09310191 0.09543925 0.09776725 0.10008031 0.1023843 0.10467939 0.10696282 0.10923552 0.11150342 0.11375564 0.11600427 0.118243 0.12047296 0.12269376 0.12490488 0.12711415 0.12931036 0.13150096 0.13368154 0.13585982 0.13803009 0.14018961 0.14234359 0.14449503 0.14663648 0.14877236 0.15089947 0.15302471 0.155141 0.15725402 0.15935959 0.16145813 0.16355132 0.16563963 0.16772494 0.1698033 0.17187555 0.17394191 0.17600722 0.17806499 0.18011745 0.18216164 0.18420446 0.18624091 0.18827655 0.19030833 0.19233052 0.19434885 0.19636357 0.19837593 0.20037883 0.20238383 0.20438058 0.20637502 0.20836358 0.21034732 0.21232885 0.21430571 0.21627763 0.21824694 0.22021326 0.22217222 0.22412743 0.22608217 0.22803347 0.22998291 0.23192295 0.23385759 0.23579759 0.23772869 0.23965799 0.24157841 0.24349944 0.24541689 0.24733152 0.24924241 0.25115108 0.25305646 0.25495687 0.25685379 0.25874221 0.26063593 0.26252242 0.26440664 0.26628698 0.26816398 0.27004031 0.27191147 0.27377527 0.27564404 0.27750921 0.27935984 0.28121741 0.28306997 0.2849209 0.28676631 0.28860828 0.29045122 0.29229007 0.29412417 0.29595331 0.29778415 0.29960719 0.30142759 0.30324755 0.30506054 0.30687771 0.30869136 0.31049896 0.31230004 0.31410149 0.3159051 0.3177027 0.31949741 0.32128578 0.32306955 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +42 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03275873 0.00083377 0.02543348 0.0448834 0.0667768 0.07915202 0.09113854 0.10280435 0.11420819 0.12538567 0.13636556 0.14716567 0.15780447 0.1683014 0.178663 0.18889865 0.19901765 0.20902392 0.21892797 0.22873221 0.23844548 0.24806675 0.25759734 0.26705022 0.27641741 0.2857055 0.29491896 0.3040543 0.31311378 0.32210299 0.33103247 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/Test_Cases/5MW_OC4_MH_Legacy/NRELOffshrBsline5MW_OC4DeepCwindSemi_ServoDyn.dat b/Test_Cases/5MW_OC4_MH_Legacy/NRELOffshrBsline5MW_OC4DeepCwindSemi_ServoDyn.dat index cf8909fc0..26d16dbeb 100644 --- a/Test_Cases/5MW_OC4_MH_Legacy/NRELOffshrBsline5MW_OC4DeepCwindSemi_ServoDyn.dat +++ b/Test_Cases/5MW_OC4_MH_Legacy/NRELOffshrBsline5MW_OC4DeepCwindSemi_ServoDyn.dat @@ -63,7 +63,7 @@ False CompNTMD - Compute nacelle tuned mass damper {true/false} (fla False CompTTMD - Compute tower tuned mass damper {true/false} (flag) "unused" TTMDfile - Name of the file for tower tuned mass damper (quoted string) [unused when CompTTMD is false] ---------------------- BLADED INTERFACE ---------------------------------------- [used only with Bladed Interface] -"../5MW_Baseline/DISCON/DISCON_OC3Hywind.dll" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] +"../5MW_Baseline/DISCON/DISCON.dll" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] "DISCON.IN" DLL_InFile - Name of input file sent to the DLL (-) [used only with Bladed Interface] "DISCON" DLL_ProcName - Name of procedure in DLL to be called (-) [case sensitive; used only with DLL Interface] "default" DLL_DT - Communication interval for dynamic library (s) (or "default") [used only with Bladed Interface] diff --git a/Test_Cases/5MW_OC4_NR_Baseline/DISCON.IN b/Test_Cases/5MW_OC4_NR_Baseline/DISCON.IN index 12916d09c..6d38f170e 100644 --- a/Test_Cases/5MW_OC4_NR_Baseline/DISCON.IN +++ b/Test_Cases/5MW_OC4_NR_Baseline/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the 5MW_Land wind turbine -! - File written using NREL Baseline Controller tuning logic on 10/01/19 +! - File written using NREL Baseline Controller tuning logic on 10/07/19 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file @@ -16,24 +16,24 @@ 1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} !------- FILTERS ---------------------------------------------------------- -1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +1.543417826848871 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] 0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] 0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] 0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.5 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [Hz]. !------- BLADE PITCH CONTROL ---------------------------------------------- -136 ! PC_GS_n - Amount of gain-scheduling table entries -0. 0.01843267 0.03012466 0.03938211 0.0473159 0.05438725 0.0608399 0.06682165 0.07243603 0.07774601 0.08280179 0.08764533 0.0922973 0.09678511 0.10113084 0.10534505 0.10944741 0.11344459 0.11734245 0.12115249 0.12488383 0.12853954 0.13212927 0.13565125 0.13911823 0.1425236 0.14587973 0.1491875 0.15244657 0.15566288 0.15883986 0.16197375 0.16506986 0.16813214 0.17115907 0.17415428 0.17711497 0.18004808 0.18295399 0.1858281 0.1886768 0.19150248 0.19430239 0.19707534 0.19983015 0.2025582 0.20526628 0.20795513 0.21062023 0.21326861 0.2158935 0.21850484 0.2210941 0.22366803 0.22622254 0.22876498 0.2312836 0.23379345 0.23628255 0.23875941 0.24122279 0.24366729 0.24610036 0.24852176 0.25092855 0.25332325 0.2557023 0.25807209 0.26042559 0.26276748 0.26510036 0.26742092 0.26973036 0.27202782 0.27431492 0.27658881 0.27885401 0.28110964 0.28336045 0.2855962 0.28782076 0.29003745 0.29224346 0.29444004 0.29663204 0.2988061 0.30097858 0.30314198 0.30529447 0.30743825 0.30958 0.31170708 0.31382687 0.31593631 0.3180419 0.32013786 0.32222978 0.32431029 0.32638663 0.32845309 0.33051357 0.33256802 0.33461455 0.33665611 0.33868284 0.34071023 0.34272963 0.34474196 0.34674528 0.34875073 0.35074041 0.35272695 0.35470654 0.35668277 0.35864961 0.36061312 0.36256798 0.36452117 0.36646633 0.36840178 0.37033735 0.3722649 0.37418622 0.37609996 0.37801477 0.37991806 0.38181864 0.38371323 0.38560453 0.38749153 0.38937202 0.39124103 0.39310673 0.39497577 0.39683082 0.39868511 ! PC_GS_angles - Gain-schedule table: pitch angles --0.02019147 -0.01950333 -0.01885443 -0.0182415 -0.01766165 -0.01711225 -0.01659098 -0.01609573 -0.01562459 -0.01517585 -0.01474794 -0.01433946 -0.0139491 -0.01357569 -0.01321814 -0.01287547 -0.01254676 -0.01223119 -0.01192797 -0.0116364 -0.01135581 -0.01108561 -0.01082521 -0.01057411 -0.0103318 -0.01009784 -0.00987181 -0.00965329 -0.00944194 -0.00923739 -0.00903933 -0.00884745 -0.00866147 -0.00848112 -0.00830614 -0.00813631 -0.0079714 -0.00781119 -0.00765549 -0.00750411 -0.00735688 -0.00721362 -0.00707417 -0.0069384 -0.00680614 -0.00667728 -0.00655167 -0.0064292 -0.00630975 -0.00619322 -0.00607949 -0.00596846 -0.00586005 -0.00575415 -0.00565069 -0.00554957 -0.00545073 -0.00535408 -0.00525955 -0.00516708 -0.00507659 -0.00498803 -0.00490133 -0.00481644 -0.00473329 -0.00465184 -0.00457204 -0.00449383 -0.00441716 -0.004342 -0.0042683 -0.00419602 -0.00412511 -0.00405553 -0.00398726 -0.00392025 -0.00385447 -0.00378988 -0.00372646 -0.00366417 -0.00360298 -0.00354286 -0.00348379 -0.00342574 -0.00336868 -0.00331258 -0.00325743 -0.00320319 -0.00314985 -0.00309739 -0.00304578 -0.002995 -0.00294503 -0.00289585 -0.00284745 -0.00279981 -0.0027529 -0.00270671 -0.00266123 -0.00261644 -0.00257232 -0.00252886 -0.00248604 -0.00244385 -0.00240228 -0.00236131 -0.00232093 -0.00228112 -0.00224188 -0.0022032 -0.00216505 -0.00212743 -0.00209033 -0.00205374 -0.00201765 -0.00198204 -0.00194691 -0.00191225 -0.00187805 -0.0018443 -0.00181099 -0.00177811 -0.00174566 -0.00171362 -0.00168199 -0.00165076 -0.00161992 -0.00158947 -0.00155939 -0.00152969 -0.00150035 -0.00147137 -0.00144274 -0.00141446 -0.00138651 -0.0013589 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains --0.00882307 -0.00856411 -0.00831992 -0.00808927 -0.00787106 -0.00766432 -0.00746816 -0.00728178 -0.00710449 -0.00693562 -0.0067746 -0.00662088 -0.00647398 -0.00633346 -0.00619891 -0.00606996 -0.00594626 -0.00582751 -0.0057134 -0.00560368 -0.00549809 -0.00539641 -0.00529842 -0.00520393 -0.00511274 -0.0050247 -0.00493964 -0.00485741 -0.00477787 -0.0047009 -0.00462637 -0.00455416 -0.00448417 -0.0044163 -0.00435046 -0.00428655 -0.00422449 -0.0041642 -0.00410561 -0.00404864 -0.00399324 -0.00393933 -0.00388685 -0.00383576 -0.00378599 -0.00373749 -0.00369023 -0.00364414 -0.00359919 -0.00355534 -0.00351254 -0.00347076 -0.00342996 -0.00339011 -0.00335117 -0.00331312 -0.00327593 -0.00323956 -0.00320399 -0.00316919 -0.00313514 -0.00310181 -0.00306918 -0.00303724 -0.00300595 -0.0029753 -0.00294526 -0.00291583 -0.00288698 -0.0028587 -0.00283096 -0.00280376 -0.00277708 -0.0027509 -0.0027252 -0.00269999 -0.00267523 -0.00265093 -0.00262706 -0.00260362 -0.00258059 -0.00255797 -0.00253574 -0.0025139 -0.00249242 -0.00247131 -0.00245056 -0.00243015 -0.00241008 -0.00239033 -0.00237091 -0.0023518 -0.002333 -0.00231449 -0.00229628 -0.00227835 -0.0022607 -0.00224332 -0.0022262 -0.00220935 -0.00219274 -0.00217639 -0.00216028 -0.0021444 -0.00212876 -0.00211334 -0.00209814 -0.00208316 -0.0020684 -0.00205384 -0.00203948 -0.00202533 -0.00201136 -0.00199759 -0.00198401 -0.00197061 -0.00195739 -0.00194435 -0.00193148 -0.00191878 -0.00190624 -0.00189387 -0.00188166 -0.0018696 -0.0018577 -0.00184595 -0.00183434 -0.00182288 -0.00181157 -0.00180039 -0.00178935 -0.00177844 -0.00176767 -0.00175702 -0.00174651 -0.00173612 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +27 ! PC_GS_n - Amount of gain-scheduling table entries +0.05852874 0.08586931 0.10789716 0.1271165 0.14453395 0.16067791 0.17585826 0.19027256 0.20405942 0.21730904 0.23010311 0.24249689 0.2545414 0.26626371 0.27770397 0.28889173 0.29983774 0.31057221 0.32109644 0.33144053 0.34160524 0.35160739 0.36145513 0.37115299 0.38071093 0.3901412 0.39943831 ! PC_GS_angles - Gain-schedule table: pitch angles +-0.01603382 -0.01396602 -0.01229584 -0.01091865 -0.00976358 -0.00878088 -0.00793467 -0.00719835 -0.00655181 -0.00597959 -0.00546956 -0.00501211 -0.00459951 -0.00422546 -0.00388481 -0.00357328 -0.00328728 -0.0030238 -0.00278028 -0.00255453 -0.00234468 -0.00214911 -0.0019664 -0.00179533 -0.00163481 -0.00148391 -0.00134179 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-0.00715561 -0.00639445 -0.00577965 -0.00527271 -0.00484752 -0.00448579 -0.0041743 -0.00390326 -0.00366527 -0.00345463 -0.00326689 -0.0030985 -0.00294662 -0.00280893 -0.00268354 -0.00256886 -0.00246359 -0.0023666 -0.00227696 -0.00219386 -0.00211661 -0.00204462 -0.00197737 -0.0019144 -0.00185531 -0.00179976 -0.00174745 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +122.90957658394467 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. 0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] 0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] @@ -41,63 +41,64 @@ 0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] -1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. -2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] +0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] !------- VS TORQUE CONTROL ------------------------------------------------ -0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] -43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +94.4 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +43093.55150917838 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +47402.906660096225 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. -91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] -2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] -5.0E+06 ! VS_RtPwr - Wind turbine rated power [W] -43093.55 ! VS_RtTq - Rated torque, [Nm]. -120.113 ! VS_RefSpd - Rated generator speed [rad/s] +0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5000000 ! VS_RtPwr - Wind turbine rated power [W] +43093.55150917838 ! VS_RtTq - Rated torque, [Nm]. +122.90957658394467 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-889.094048017944 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-172.0461874545648 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.4 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. !------- SETPOINT SMOOTHER --------------------------------------------- 30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. 0.0001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. !------- WIND SPEED ESTIMATOR --------------------------------------------- -63.0 ! WE_BladeRadius - Blade length [m] +63.0 ! WE_BladeRadius - Blade length [m] 4 ! WE_CP_n - Amount of parameters in the Cp array -14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function -20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] -97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +40469564.444 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1.225 ! WE_RhoAir - Air density, [kg m^-3] "../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) -320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -23 ! WE_FOPoles_N - Number of first-order system poles used in EKF -3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles +320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +42 ! WE_FOPoles_N - Number of first-order system poles used in EKF + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02665071 -0.02998205 -0.03331339 -0.03664473 -0.03997606 -0.0433074 -0.04663874 -0.04997008 -0.05330142 -0.05663276 -0.0599641 -0.06329543 -0.06662677 -0.06995811 -0.07328945 -0.06321278 -0.07469151 -0.08828579 -0.10297822 -0.11842623 -0.13448765 -0.15120764 -0.168455 -0.18635293 -0.20483641 -0.22395323 -0.24348262 -0.26365771 -0.2842596 -0.30535287 -0.32683352 -0.3487705 -0.37113879 -0.39376001 -0.41675049 -0.44017539 -0.46432564 -0.4888057 -0.51273708 -0.53554138 -0.55932133 -0.58645605 ! WE_FOPoles - First order system poles !------- YAW CONTROL ------------------------------------------------------ -1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] -0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) --0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp --0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki -0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. -1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. -0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad] -1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] -0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] -0.0034906 ! Y_Rate - Yaw rate [rad/s] +0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.0 ! Y_MErrSet - Yaw alignment error, set point [rad] +0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0 ! Y_Rate - Yaw rate [rad/s] !------- TOWER FORE-AFT DAMPING ------------------------------------------- -1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag -0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] -0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] +0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] !------- PEAK SHAVING ------------------------------------------- -210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) - 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.02962541 -0.02230897 -0.01548946 -0.00915689 -0.00323985 0.00231633 0.00755924 0.01252064 0.01723337 0.02171883 0.02600713 0.03010809 0.03403543 0.03780094 0.04141197 0.0448834 0.04301121 0.04572902 0.04841563 0.05107257 0.05370175 0.05630738 0.05888727 0.06144604 0.06398009 0.06649806 0.06899513 0.07147461 0.07393783 0.0763848 0.07881322 0.08122765 0.08363032 0.08601684 0.0883911 0.09075519 0.09310191 0.09543925 0.09776725 0.10008031 0.1023843 0.10467939 0.10696282 0.10923552 0.11150342 0.11375564 0.11600427 0.118243 0.12047296 0.12269376 0.12490488 0.12711415 0.12931036 0.13150096 0.13368154 0.13585982 0.13803009 0.14018961 0.14234359 0.14449503 0.14663648 0.14877236 0.15089947 0.15302471 0.155141 0.15725402 0.15935959 0.16145813 0.16355132 0.16563963 0.16772494 0.1698033 0.17187555 0.17394191 0.17600722 0.17806499 0.18011745 0.18216164 0.18420446 0.18624091 0.18827655 0.19030833 0.19233052 0.19434885 0.19636357 0.19837593 0.20037883 0.20238383 0.20438058 0.20637502 0.20836358 0.21034732 0.21232885 0.21430571 0.21627763 0.21824694 0.22021326 0.22217222 0.22412743 0.22608217 0.22803347 0.22998291 0.23192295 0.23385759 0.23579759 0.23772869 0.23965799 0.24157841 0.24349944 0.24541689 0.24733152 0.24924241 0.25115108 0.25305646 0.25495687 0.25685379 0.25874221 0.26063593 0.26252242 0.26440664 0.26628698 0.26816398 0.27004031 0.27191147 0.27377527 0.27564404 0.27750921 0.27935984 0.28121741 0.28306997 0.2849209 0.28676631 0.28860828 0.29045122 0.29229007 0.29412417 0.29595331 0.29778415 0.29960719 0.30142759 0.30324755 0.30506054 0.30687771 0.30869136 0.31049896 0.31230004 0.31410149 0.3159051 0.3177027 0.31949741 0.32128578 0.32306955 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +42 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03275873 0.00083377 0.02543348 0.0448834 0.0667768 0.07915202 0.09113854 0.10280435 0.11420819 0.12538567 0.13636556 0.14716567 0.15780447 0.1683014 0.178663 0.18889865 0.19901765 0.20902392 0.21892797 0.22873221 0.23844548 0.24806675 0.25759734 0.26705022 0.27641741 0.2857055 0.29491896 0.3040543 0.31311378 0.32210299 0.33103247 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/Test_Cases/5MW_OC4_NR_Legacy/NRELOffshrBsline5MW_OC4DeepCwindSemi_ServoDyn.dat b/Test_Cases/5MW_OC4_NR_Legacy/NRELOffshrBsline5MW_OC4DeepCwindSemi_ServoDyn.dat index cf8909fc0..26d16dbeb 100644 --- a/Test_Cases/5MW_OC4_NR_Legacy/NRELOffshrBsline5MW_OC4DeepCwindSemi_ServoDyn.dat +++ b/Test_Cases/5MW_OC4_NR_Legacy/NRELOffshrBsline5MW_OC4DeepCwindSemi_ServoDyn.dat @@ -63,7 +63,7 @@ False CompNTMD - Compute nacelle tuned mass damper {true/false} (fla False CompTTMD - Compute tower tuned mass damper {true/false} (flag) "unused" TTMDfile - Name of the file for tower tuned mass damper (quoted string) [unused when CompTTMD is false] ---------------------- BLADED INTERFACE ---------------------------------------- [used only with Bladed Interface] -"../5MW_Baseline/DISCON/DISCON_OC3Hywind.dll" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] +"../5MW_Baseline/DISCON/DISCON.dll" DLL_FileName - Name/location of the dynamic library {.dll [Windows] or .so [Linux]} in the Bladed-DLL format (-) [used only with Bladed Interface] "DISCON.IN" DLL_InFile - Name of input file sent to the DLL (-) [used only with Bladed Interface] "DISCON" DLL_ProcName - Name of procedure in DLL to be called (-) [case sensitive; used only with DLL Interface] "default" DLL_DT - Communication interval for dynamic library (s) (or "default") [used only with Bladed Interface] diff --git a/Test_Cases/5MW_Step_Baseline/DISCON.IN b/Test_Cases/5MW_Step_Baseline/DISCON.IN index 12916d09c..6d38f170e 100644 --- a/Test_Cases/5MW_Step_Baseline/DISCON.IN +++ b/Test_Cases/5MW_Step_Baseline/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the 5MW_Land wind turbine -! - File written using NREL Baseline Controller tuning logic on 10/01/19 +! - File written using NREL Baseline Controller tuning logic on 10/07/19 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file @@ -16,24 +16,24 @@ 1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} !------- FILTERS ---------------------------------------------------------- -1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +1.543417826848871 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] 0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] 0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] 0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.5 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [Hz]. !------- BLADE PITCH CONTROL ---------------------------------------------- -136 ! PC_GS_n - Amount of gain-scheduling table entries -0. 0.01843267 0.03012466 0.03938211 0.0473159 0.05438725 0.0608399 0.06682165 0.07243603 0.07774601 0.08280179 0.08764533 0.0922973 0.09678511 0.10113084 0.10534505 0.10944741 0.11344459 0.11734245 0.12115249 0.12488383 0.12853954 0.13212927 0.13565125 0.13911823 0.1425236 0.14587973 0.1491875 0.15244657 0.15566288 0.15883986 0.16197375 0.16506986 0.16813214 0.17115907 0.17415428 0.17711497 0.18004808 0.18295399 0.1858281 0.1886768 0.19150248 0.19430239 0.19707534 0.19983015 0.2025582 0.20526628 0.20795513 0.21062023 0.21326861 0.2158935 0.21850484 0.2210941 0.22366803 0.22622254 0.22876498 0.2312836 0.23379345 0.23628255 0.23875941 0.24122279 0.24366729 0.24610036 0.24852176 0.25092855 0.25332325 0.2557023 0.25807209 0.26042559 0.26276748 0.26510036 0.26742092 0.26973036 0.27202782 0.27431492 0.27658881 0.27885401 0.28110964 0.28336045 0.2855962 0.28782076 0.29003745 0.29224346 0.29444004 0.29663204 0.2988061 0.30097858 0.30314198 0.30529447 0.30743825 0.30958 0.31170708 0.31382687 0.31593631 0.3180419 0.32013786 0.32222978 0.32431029 0.32638663 0.32845309 0.33051357 0.33256802 0.33461455 0.33665611 0.33868284 0.34071023 0.34272963 0.34474196 0.34674528 0.34875073 0.35074041 0.35272695 0.35470654 0.35668277 0.35864961 0.36061312 0.36256798 0.36452117 0.36646633 0.36840178 0.37033735 0.3722649 0.37418622 0.37609996 0.37801477 0.37991806 0.38181864 0.38371323 0.38560453 0.38749153 0.38937202 0.39124103 0.39310673 0.39497577 0.39683082 0.39868511 ! PC_GS_angles - Gain-schedule table: pitch angles --0.02019147 -0.01950333 -0.01885443 -0.0182415 -0.01766165 -0.01711225 -0.01659098 -0.01609573 -0.01562459 -0.01517585 -0.01474794 -0.01433946 -0.0139491 -0.01357569 -0.01321814 -0.01287547 -0.01254676 -0.01223119 -0.01192797 -0.0116364 -0.01135581 -0.01108561 -0.01082521 -0.01057411 -0.0103318 -0.01009784 -0.00987181 -0.00965329 -0.00944194 -0.00923739 -0.00903933 -0.00884745 -0.00866147 -0.00848112 -0.00830614 -0.00813631 -0.0079714 -0.00781119 -0.00765549 -0.00750411 -0.00735688 -0.00721362 -0.00707417 -0.0069384 -0.00680614 -0.00667728 -0.00655167 -0.0064292 -0.00630975 -0.00619322 -0.00607949 -0.00596846 -0.00586005 -0.00575415 -0.00565069 -0.00554957 -0.00545073 -0.00535408 -0.00525955 -0.00516708 -0.00507659 -0.00498803 -0.00490133 -0.00481644 -0.00473329 -0.00465184 -0.00457204 -0.00449383 -0.00441716 -0.004342 -0.0042683 -0.00419602 -0.00412511 -0.00405553 -0.00398726 -0.00392025 -0.00385447 -0.00378988 -0.00372646 -0.00366417 -0.00360298 -0.00354286 -0.00348379 -0.00342574 -0.00336868 -0.00331258 -0.00325743 -0.00320319 -0.00314985 -0.00309739 -0.00304578 -0.002995 -0.00294503 -0.00289585 -0.00284745 -0.00279981 -0.0027529 -0.00270671 -0.00266123 -0.00261644 -0.00257232 -0.00252886 -0.00248604 -0.00244385 -0.00240228 -0.00236131 -0.00232093 -0.00228112 -0.00224188 -0.0022032 -0.00216505 -0.00212743 -0.00209033 -0.00205374 -0.00201765 -0.00198204 -0.00194691 -0.00191225 -0.00187805 -0.0018443 -0.00181099 -0.00177811 -0.00174566 -0.00171362 -0.00168199 -0.00165076 -0.00161992 -0.00158947 -0.00155939 -0.00152969 -0.00150035 -0.00147137 -0.00144274 -0.00141446 -0.00138651 -0.0013589 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains --0.00882307 -0.00856411 -0.00831992 -0.00808927 -0.00787106 -0.00766432 -0.00746816 -0.00728178 -0.00710449 -0.00693562 -0.0067746 -0.00662088 -0.00647398 -0.00633346 -0.00619891 -0.00606996 -0.00594626 -0.00582751 -0.0057134 -0.00560368 -0.00549809 -0.00539641 -0.00529842 -0.00520393 -0.00511274 -0.0050247 -0.00493964 -0.00485741 -0.00477787 -0.0047009 -0.00462637 -0.00455416 -0.00448417 -0.0044163 -0.00435046 -0.00428655 -0.00422449 -0.0041642 -0.00410561 -0.00404864 -0.00399324 -0.00393933 -0.00388685 -0.00383576 -0.00378599 -0.00373749 -0.00369023 -0.00364414 -0.00359919 -0.00355534 -0.00351254 -0.00347076 -0.00342996 -0.00339011 -0.00335117 -0.00331312 -0.00327593 -0.00323956 -0.00320399 -0.00316919 -0.00313514 -0.00310181 -0.00306918 -0.00303724 -0.00300595 -0.0029753 -0.00294526 -0.00291583 -0.00288698 -0.0028587 -0.00283096 -0.00280376 -0.00277708 -0.0027509 -0.0027252 -0.00269999 -0.00267523 -0.00265093 -0.00262706 -0.00260362 -0.00258059 -0.00255797 -0.00253574 -0.0025139 -0.00249242 -0.00247131 -0.00245056 -0.00243015 -0.00241008 -0.00239033 -0.00237091 -0.0023518 -0.002333 -0.00231449 -0.00229628 -0.00227835 -0.0022607 -0.00224332 -0.0022262 -0.00220935 -0.00219274 -0.00217639 -0.00216028 -0.0021444 -0.00212876 -0.00211334 -0.00209814 -0.00208316 -0.0020684 -0.00205384 -0.00203948 -0.00202533 -0.00201136 -0.00199759 -0.00198401 -0.00197061 -0.00195739 -0.00194435 -0.00193148 -0.00191878 -0.00190624 -0.00189387 -0.00188166 -0.0018696 -0.0018577 -0.00184595 -0.00183434 -0.00182288 -0.00181157 -0.00180039 -0.00178935 -0.00177844 -0.00176767 -0.00175702 -0.00174651 -0.00173612 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +27 ! PC_GS_n - Amount of gain-scheduling table entries +0.05852874 0.08586931 0.10789716 0.1271165 0.14453395 0.16067791 0.17585826 0.19027256 0.20405942 0.21730904 0.23010311 0.24249689 0.2545414 0.26626371 0.27770397 0.28889173 0.29983774 0.31057221 0.32109644 0.33144053 0.34160524 0.35160739 0.36145513 0.37115299 0.38071093 0.3901412 0.39943831 ! PC_GS_angles - Gain-schedule table: pitch angles +-0.01603382 -0.01396602 -0.01229584 -0.01091865 -0.00976358 -0.00878088 -0.00793467 -0.00719835 -0.00655181 -0.00597959 -0.00546956 -0.00501211 -0.00459951 -0.00422546 -0.00388481 -0.00357328 -0.00328728 -0.0030238 -0.00278028 -0.00255453 -0.00234468 -0.00214911 -0.0019664 -0.00179533 -0.00163481 -0.00148391 -0.00134179 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-0.00715561 -0.00639445 -0.00577965 -0.00527271 -0.00484752 -0.00448579 -0.0041743 -0.00390326 -0.00366527 -0.00345463 -0.00326689 -0.0030985 -0.00294662 -0.00280893 -0.00268354 -0.00256886 -0.00246359 -0.0023666 -0.00227696 -0.00219386 -0.00211661 -0.00204462 -0.00197737 -0.0019144 -0.00185531 -0.00179976 -0.00174745 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +122.90957658394467 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. 0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] 0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] @@ -41,63 +41,64 @@ 0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] -1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. -2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] +0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] !------- VS TORQUE CONTROL ------------------------------------------------ -0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] -43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +94.4 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +43093.55150917838 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +47402.906660096225 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. -91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] -2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] -5.0E+06 ! VS_RtPwr - Wind turbine rated power [W] -43093.55 ! VS_RtTq - Rated torque, [Nm]. -120.113 ! VS_RefSpd - Rated generator speed [rad/s] +0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5000000 ! VS_RtPwr - Wind turbine rated power [W] +43093.55150917838 ! VS_RtTq - Rated torque, [Nm]. +122.90957658394467 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-889.094048017944 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-172.0461874545648 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.4 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. !------- SETPOINT SMOOTHER --------------------------------------------- 30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. 0.0001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. !------- WIND SPEED ESTIMATOR --------------------------------------------- -63.0 ! WE_BladeRadius - Blade length [m] +63.0 ! WE_BladeRadius - Blade length [m] 4 ! WE_CP_n - Amount of parameters in the Cp array -14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function -20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] -97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +40469564.444 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1.225 ! WE_RhoAir - Air density, [kg m^-3] "../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) -320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -23 ! WE_FOPoles_N - Number of first-order system poles used in EKF -3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles +320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +42 ! WE_FOPoles_N - Number of first-order system poles used in EKF + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02665071 -0.02998205 -0.03331339 -0.03664473 -0.03997606 -0.0433074 -0.04663874 -0.04997008 -0.05330142 -0.05663276 -0.0599641 -0.06329543 -0.06662677 -0.06995811 -0.07328945 -0.06321278 -0.07469151 -0.08828579 -0.10297822 -0.11842623 -0.13448765 -0.15120764 -0.168455 -0.18635293 -0.20483641 -0.22395323 -0.24348262 -0.26365771 -0.2842596 -0.30535287 -0.32683352 -0.3487705 -0.37113879 -0.39376001 -0.41675049 -0.44017539 -0.46432564 -0.4888057 -0.51273708 -0.53554138 -0.55932133 -0.58645605 ! WE_FOPoles - First order system poles !------- YAW CONTROL ------------------------------------------------------ -1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] -0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) --0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp --0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki -0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. -1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. -0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad] -1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] -0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] -0.0034906 ! Y_Rate - Yaw rate [rad/s] +0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.0 ! Y_MErrSet - Yaw alignment error, set point [rad] +0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0 ! Y_Rate - Yaw rate [rad/s] !------- TOWER FORE-AFT DAMPING ------------------------------------------- -1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag -0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] -0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] +0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] !------- PEAK SHAVING ------------------------------------------- -210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) - 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.02962541 -0.02230897 -0.01548946 -0.00915689 -0.00323985 0.00231633 0.00755924 0.01252064 0.01723337 0.02171883 0.02600713 0.03010809 0.03403543 0.03780094 0.04141197 0.0448834 0.04301121 0.04572902 0.04841563 0.05107257 0.05370175 0.05630738 0.05888727 0.06144604 0.06398009 0.06649806 0.06899513 0.07147461 0.07393783 0.0763848 0.07881322 0.08122765 0.08363032 0.08601684 0.0883911 0.09075519 0.09310191 0.09543925 0.09776725 0.10008031 0.1023843 0.10467939 0.10696282 0.10923552 0.11150342 0.11375564 0.11600427 0.118243 0.12047296 0.12269376 0.12490488 0.12711415 0.12931036 0.13150096 0.13368154 0.13585982 0.13803009 0.14018961 0.14234359 0.14449503 0.14663648 0.14877236 0.15089947 0.15302471 0.155141 0.15725402 0.15935959 0.16145813 0.16355132 0.16563963 0.16772494 0.1698033 0.17187555 0.17394191 0.17600722 0.17806499 0.18011745 0.18216164 0.18420446 0.18624091 0.18827655 0.19030833 0.19233052 0.19434885 0.19636357 0.19837593 0.20037883 0.20238383 0.20438058 0.20637502 0.20836358 0.21034732 0.21232885 0.21430571 0.21627763 0.21824694 0.22021326 0.22217222 0.22412743 0.22608217 0.22803347 0.22998291 0.23192295 0.23385759 0.23579759 0.23772869 0.23965799 0.24157841 0.24349944 0.24541689 0.24733152 0.24924241 0.25115108 0.25305646 0.25495687 0.25685379 0.25874221 0.26063593 0.26252242 0.26440664 0.26628698 0.26816398 0.27004031 0.27191147 0.27377527 0.27564404 0.27750921 0.27935984 0.28121741 0.28306997 0.2849209 0.28676631 0.28860828 0.29045122 0.29229007 0.29412417 0.29595331 0.29778415 0.29960719 0.30142759 0.30324755 0.30506054 0.30687771 0.30869136 0.31049896 0.31230004 0.31410149 0.3159051 0.3177027 0.31949741 0.32128578 0.32306955 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +42 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03275873 0.00083377 0.02543348 0.0448834 0.0667768 0.07915202 0.09113854 0.10280435 0.11420819 0.12538567 0.13636556 0.14716567 0.15780447 0.1683014 0.178663 0.18889865 0.19901765 0.20902392 0.21892797 0.22873221 0.23844548 0.24806675 0.25759734 0.26705022 0.27641741 0.2857055 0.29491896 0.3040543 0.31311378 0.32210299 0.33103247 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/Tune_Cases/Cp_Ct_Cq.txt b/Tune_Cases/Cp_Ct_Cq.txt new file mode 100644 index 000000000..01972f4f2 --- /dev/null +++ b/Tune_Cases/Cp_Ct_Cq.txt @@ -0,0 +1,105 @@ +# Pitch angle vector - x axis (matrix columns) (deg) +-1.00 -0.50 0.00 0.50 1.00 1.50 2.00 2.50 3.00 3.50 4.00 4.50 5.00 5.50 6.00 6.50 7.00 7.50 8.00 8.50 9.00 9.50 10.00 10.50 11.00 11.50 12.00 12.50 13.00 13.50 14.00 14.50 15.00 15.50 16.00 16.50 17.00 17.50 18.00 18.50 19.00 19.50 20.00 20.50 21.00 21.50 22.00 22.50 23.00 23.50 24.00 24.50 +# TSR vector - y axis (matrix rows) (-) +0.50 1.00 1.50 2.00 2.50 3.00 3.50 4.00 4.50 5.00 5.50 6.00 6.50 7.00 7.50 8.00 8.50 9.00 9.50 10.00 10.50 11.00 11.50 12.00 12.50 13.00 13.50 14.00 14.50 +# Wind speed vector - z axis (m/s) +3.00 + +# Power coefficient + +0.00192 0.00206 0.00220 0.00234 0.00248 0.00262 0.00276 0.00290 0.00304 0.00318 0.00331 0.00345 0.00358 0.00372 0.00385 0.00398 0.00411 0.00424 0.00437 0.00449 0.00462 0.00474 0.00486 0.00498 0.00510 0.00522 0.00534 0.00545 0.00556 0.00567 0.00578 0.00589 0.00600 0.00610 0.00621 0.00631 0.00641 0.00650 0.00660 0.00670 0.00679 0.00688 0.00697 0.00706 0.00714 0.00723 0.00731 0.00740 0.00748 0.00756 0.00764 0.00772 +0.00415 0.00448 0.00480 0.00512 0.00544 0.00576 0.00607 0.00638 0.00669 0.00700 0.00731 0.00761 0.00791 0.00821 0.00851 0.00880 0.00910 0.00939 0.00969 0.00998 0.01027 0.01057 0.01087 0.01117 0.01147 0.01178 0.01209 0.01240 0.01273 0.01306 0.01340 0.01374 0.01410 0.01447 0.01485 0.01523 0.01564 0.01605 0.01648 0.01692 0.01737 0.01784 0.01831 0.01880 0.01930 0.01981 0.02033 0.02086 0.02139 0.02193 0.02247 0.02301 +0.00743 0.00811 0.00880 0.00950 0.01021 0.01094 0.01167 0.01243 0.01319 0.01398 0.01479 0.01561 0.01646 0.01733 0.01823 0.01915 0.02009 0.02106 0.02205 0.02306 0.02410 0.02516 0.02624 0.02733 0.02844 0.02956 0.03069 0.03183 0.03297 0.03410 0.03523 0.03635 0.03746 0.03855 0.03962 0.04067 0.04169 0.04268 0.04363 0.04454 0.04541 0.04623 0.04700 0.04772 0.04838 0.04898 0.04953 0.05001 0.05043 0.05079 0.05107 0.05130 +0.01726 0.01902 0.02082 0.02267 0.02457 0.02650 0.02846 0.03047 0.03250 0.03455 0.03662 0.03870 0.04079 0.04288 0.04496 0.04702 0.04907 0.05109 0.05307 0.05501 0.05690 0.05875 0.06053 0.06225 0.06390 0.06547 0.06696 0.06837 0.06969 0.07091 0.07203 0.07305 0.07396 0.07476 0.07545 0.07602 0.07648 0.07683 0.07706 0.07718 0.07718 0.07707 0.07684 0.07649 0.07604 0.07548 0.07483 0.07407 0.07322 0.07228 0.07125 0.07013 +0.04260 0.04607 0.04954 0.05300 0.05644 0.05983 0.06318 0.06648 0.06970 0.07285 0.07592 0.07889 0.08177 0.08453 0.08718 0.08971 0.09211 0.09438 0.09650 0.09846 0.10026 0.10189 0.10335 0.10463 0.10572 0.10664 0.10737 0.10791 0.10827 0.10845 0.10843 0.10824 0.10787 0.10733 0.10663 0.10577 0.10476 0.10360 0.10230 0.10084 0.09924 0.09747 0.09554 0.09344 0.09116 0.08869 0.08603 0.08318 0.08016 0.07696 0.07359 0.07007 +0.08322 0.08806 0.09277 0.09734 0.10177 0.10604 0.11014 0.11407 0.11782 0.12137 0.12471 0.12784 0.13073 0.13338 0.13578 0.13791 0.13977 0.14135 0.14266 0.14370 0.14446 0.14494 0.14516 0.14511 0.14480 0.14424 0.14344 0.14240 0.14113 0.13963 0.13789 0.13592 0.13370 0.13123 0.12848 0.12544 0.12212 0.11852 0.11465 0.11051 0.10613 0.10150 0.09665 0.09158 0.08630 0.08081 0.07513 0.06927 0.06325 0.05711 0.05084 0.04446 +0.13323 0.13894 0.14440 0.14959 0.15452 0.15915 0.16347 0.16747 0.17112 0.17440 0.17730 0.17983 0.18198 0.18375 0.18515 0.18617 0.18681 0.18707 0.18694 0.18643 0.18556 0.18434 0.18278 0.18086 0.17859 0.17593 0.17286 0.16937 0.16548 0.16119 0.15652 0.15147 0.14607 0.14032 0.13423 0.12781 0.12107 0.11404 0.10676 0.09924 0.09151 0.08359 0.07550 0.06725 0.05887 0.05036 0.04174 0.03302 0.02420 0.01530 0.00631 -0.00274 +0.18876 0.19502 0.20088 0.20631 0.21128 0.21579 0.21983 0.22338 0.22644 0.22900 0.23103 0.23251 0.23344 0.23380 0.23362 0.23290 0.23164 0.22982 0.22744 0.22447 0.22092 0.21684 0.21220 0.20704 0.20137 0.19521 0.18857 0.18145 0.17387 0.16589 0.15754 0.14884 0.13982 0.13050 0.12089 0.11103 0.10093 0.09061 0.08009 0.06940 0.05853 0.04751 0.03636 0.02507 0.01367 0.00214 -0.00950 -0.02125 -0.03309 -0.04501 -0.05698 -0.06898 +0.24795 0.25464 0.26077 0.26629 0.27116 0.27536 0.27882 0.28152 0.28341 0.28446 0.28465 0.28396 0.28238 0.27996 0.27676 0.27280 0.26812 0.26278 0.25677 0.25011 0.24281 0.23493 0.22652 0.21760 0.20822 0.19839 0.18814 0.17747 0.16642 0.15499 0.14320 0.13107 0.11862 0.10589 0.09289 0.07964 0.06618 0.05251 0.03866 0.02465 0.01046 -0.00388 -0.01839 -0.03308 -0.04792 -0.06292 -0.07803 -0.09322 -0.10843 -0.12361 -0.13873 -0.15373 +0.31164 0.31867 0.32473 0.32970 0.33348 0.33597 0.33710 0.33692 0.33551 0.33295 0.32937 0.32487 0.31950 0.31329 0.30631 0.29862 0.29027 0.28131 0.27176 0.26165 0.25099 0.23980 0.22809 0.21586 0.20312 0.18989 0.17617 0.16200 0.14739 0.13237 0.11697 0.10124 0.08519 0.06886 0.05227 0.03544 0.01838 0.00110 -0.01641 -0.03415 -0.05214 -0.07039 -0.08887 -0.10756 -0.12640 -0.14529 -0.16416 -0.18290 -0.20145 -0.21973 -0.23774 -0.25550 +0.37693 0.38214 0.38555 0.38711 0.38693 0.38520 0.38209 0.37776 0.37239 0.36613 0.35907 0.35125 0.34272 0.33348 0.32358 0.31301 0.30179 0.28992 0.27739 0.26422 0.25040 0.23594 0.22084 0.20513 0.18882 0.17193 0.15450 0.13657 0.11817 0.09934 0.08012 0.06054 0.04063 0.02041 -0.00012 -0.02095 -0.04210 -0.06358 -0.08542 -0.10762 -0.13016 -0.15298 -0.17599 -0.19906 -0.22203 -0.24475 -0.26713 -0.28907 -0.31059 -0.33176 -0.35278 -0.37390 +0.42841 0.42925 0.42814 0.42545 0.42149 0.41647 0.41054 0.40377 0.39617 0.38776 0.37855 0.36854 0.35775 0.34616 0.33379 0.32062 0.30665 0.29188 0.27629 0.25990 0.24271 0.22473 0.20599 0.18652 0.16634 0.14551 0.12408 0.10209 0.07959 0.05662 0.03322 0.00939 -0.01483 -0.03947 -0.06453 -0.09005 -0.11604 -0.14253 -0.16949 -0.19684 -0.22447 -0.25220 -0.27980 -0.30706 -0.33382 -0.35998 -0.38551 -0.41052 -0.43526 -0.46009 -0.48538 -0.51139 +0.45558 0.45407 0.45129 0.44740 0.44249 0.43658 0.42967 0.42176 0.41288 0.40302 0.39219 0.38038 0.36758 0.35379 0.33899 0.32317 0.30633 0.28846 0.26956 0.24966 0.22877 0.20693 0.18418 0.16057 0.13617 0.11104 0.08522 0.05879 0.03177 0.00421 -0.02388 -0.05251 -0.08168 -0.11145 -0.14184 -0.17286 -0.20451 -0.23672 -0.26937 -0.30223 -0.33505 -0.36753 -0.39940 -0.43048 -0.46070 -0.49013 -0.51902 -0.54782 -0.57705 -0.60724 -0.63871 -0.67140 +0.46594 0.46532 0.46348 0.46037 0.45593 0.45018 0.44311 0.43475 0.42510 0.41418 0.40197 0.38847 0.37369 0.35760 0.34020 0.32149 0.30147 0.28017 0.25759 0.23378 0.20879 0.18268 0.15553 0.12740 0.09836 0.06850 0.03787 0.00652 -0.02551 -0.05823 -0.09164 -0.12578 -0.16071 -0.19643 -0.23295 -0.27024 -0.30819 -0.34657 -0.38513 -0.42351 -0.46132 -0.49821 -0.53401 -0.56869 -0.60241 -0.63565 -0.66905 -0.70331 -0.73912 -0.77686 -0.81641 -0.85729 +0.46660 0.46835 0.46864 0.46730 0.46426 0.45943 0.45280 0.44440 0.43424 0.42236 0.40878 0.39352 0.37657 0.35796 0.33767 0.31574 0.29219 0.26705 0.24039 0.21227 0.18277 0.15200 0.12002 0.08693 0.05282 0.01777 -0.01817 -0.05498 -0.09265 -0.13122 -0.17073 -0.21122 -0.25270 -0.29516 -0.33854 -0.38268 -0.42730 -0.47209 -0.51659 -0.56028 -0.60273 -0.64377 -0.68340 -0.72193 -0.76004 -0.79857 -0.83838 -0.88036 -0.92508 -0.97245 -1.02186 -1.07203 +0.46121 0.46588 0.46883 0.46984 0.46868 0.46524 0.45942 0.45121 0.44067 0.42785 0.41283 0.39564 0.37632 0.35489 0.33140 0.30589 0.27842 0.24907 0.21792 0.18510 0.15069 0.11481 0.07756 0.03906 -0.00061 -0.04138 -0.08323 -0.12615 -0.17020 -0.21542 -0.26184 -0.30948 -0.35829 -0.40819 -0.45900 -0.51040 -0.56199 -0.61323 -0.66346 -0.71215 -0.75907 -0.80429 -0.84824 -0.89178 -0.93590 -0.98163 -1.03016 -1.08237 -1.13832 -1.19729 -1.25762 -1.31711 +0.45175 0.45925 0.46502 0.46860 0.46962 0.46784 0.46310 0.45530 0.44448 0.43072 0.41415 0.39486 0.37291 0.34839 0.32136 0.29191 0.26015 0.22620 0.19018 0.15222 0.11245 0.07101 0.02802 -0.01640 -0.06219 -0.10929 -0.15772 -0.20752 -0.25875 -0.31144 -0.36558 -0.42113 -0.47798 -0.53594 -0.59465 -0.65365 -0.71231 -0.76984 -0.82555 -0.87917 -0.93075 -0.98082 -1.03035 -1.08043 -1.13235 -1.18762 -1.24755 -1.31258 -1.38206 -1.45391 -1.52519 -1.59322 +0.44026 0.44977 0.45793 0.46400 0.46732 0.46739 0.46391 0.45670 0.44569 0.43098 0.41275 0.39116 0.36635 0.33843 0.30753 0.27379 0.23737 0.19842 0.15709 0.11355 0.06795 0.02046 -0.02880 -0.07972 -0.13224 -0.18636 -0.24214 -0.29964 -0.35887 -0.41985 -0.48249 -0.54669 -0.61223 -0.67877 -0.74578 -0.81257 -0.87822 -0.94190 -1.00317 -1.06205 -1.11903 -1.17511 -1.23154 -1.28985 -1.35186 -1.41951 -1.49385 -1.57439 -1.65884 -1.74349 -1.82493 -1.90097 +0.42765 0.43872 0.44855 0.45662 0.46208 0.46404 0.46194 0.45541 0.44430 0.42862 0.40862 0.38455 0.35660 0.32499 0.28989 0.25150 0.21002 0.16564 0.11856 0.06896 0.01703 -0.03705 -0.09314 -0.15118 -0.21114 -0.27306 -0.33702 -0.40304 -0.47111 -0.54117 -0.61306 -0.68661 -0.76145 -0.83704 -0.91264 -0.98727 -1.05993 -1.12994 -1.19719 -1.26201 -1.32534 -1.38857 -1.45346 -1.52222 -1.59738 -1.68081 -1.77243 -1.87010 -1.96954 -2.06638 -2.15758 -2.24220 +0.41382 0.42649 0.43766 0.44717 0.45430 0.45800 0.45726 0.45149 0.44031 0.42366 0.40176 0.37499 0.34366 0.30805 0.26841 0.22499 0.17803 0.12778 0.07445 0.01828 -0.04051 -0.10174 -0.16531 -0.23116 -0.29933 -0.36988 -0.44285 -0.51824 -0.59597 -0.67588 -0.75778 -0.84134 -0.92602 -1.01106 -1.09549 -1.17815 -1.25809 -1.33492 -1.40870 -1.48017 -1.55079 -1.62258 -1.69814 -1.78051 -1.87239 -1.97455 -2.08537 -2.20056 -2.31465 -2.42343 -2.52484 -2.61933 +0.39858 0.41296 0.42549 0.43611 0.44445 0.44951 0.45001 0.44496 0.43373 0.41606 0.39215 0.36249 0.32751 0.28758 0.24303 0.19417 0.14129 0.08468 0.02461 -0.03865 -0.10488 -0.17390 -0.24563 -0.32007 -0.39728 -0.47730 -0.56015 -0.64574 -0.73392 -0.82447 -0.91709 -1.01129 -1.10633 -1.20126 -1.29486 -1.38595 -1.47369 -1.55776 -1.63853 -1.71740 -1.79660 -1.87913 -1.96847 -2.06797 -2.17961 -2.30272 -2.43374 -2.56642 -2.69507 -2.81609 -2.92890 -3.03469 +0.38179 0.39801 0.41193 0.42361 0.43282 0.43885 0.44029 0.43585 0.42453 0.40581 0.37976 0.34700 0.30810 0.26352 0.21368 0.15895 0.09968 0.03621 -0.03114 -0.10206 -0.17635 -0.25383 -0.33448 -0.41833 -0.50543 -0.59579 -0.68937 -0.78599 -0.88543 -0.98739 -1.09144 -1.19692 -1.30292 -1.40825 -1.51156 -1.61160 -1.70748 -1.79906 -1.88738 -1.97480 -2.06467 -2.16088 -2.26730 -2.38704 -2.52092 -2.66665 -2.81831 -2.96862 -3.11209 -3.24634 -3.37192 -3.49051 +0.36331 0.38148 0.39686 0.40962 0.41955 0.42622 0.42826 0.42421 0.41272 0.39288 0.36457 0.32849 0.28537 0.23578 0.18024 0.11919 0.05305 -0.01780 -0.09298 -0.17218 -0.25519 -0.34189 -0.43226 -0.52636 -0.62422 -0.72581 -0.83096 -0.93945 -1.05097 -1.16512 -1.28134 -1.39881 -1.51645 -1.63286 -1.74648 -1.85580 -1.95997 -2.05939 -2.15625 -2.25414 -2.35738 -2.47034 -2.59689 -2.73956 -2.89783 -3.06732 -3.24004 -3.40835 -3.56739 -3.71617 -3.85601 -3.98895 +0.34306 0.36328 0.38018 0.39402 0.40461 0.41171 0.41406 0.41011 0.39829 0.37723 0.34654 0.30690 0.25925 0.20429 0.14263 0.07478 0.00125 -0.07752 -0.16113 -0.24927 -0.34172 -0.43841 -0.53935 -0.64459 -0.75411 -0.86778 -0.98537 -1.10658 -1.23100 -1.35815 -1.48736 -1.61766 -1.74776 -1.87598 -2.00029 -2.11900 -2.23158 -2.33962 -2.44669 -2.55750 -2.67694 -2.80952 -2.95901 -3.12705 -3.31156 -3.50572 -3.70011 -3.88706 -4.06282 -4.22759 -4.38323 -4.53215 +0.32095 0.34328 0.36179 0.37673 0.38795 0.39534 0.39774 0.39361 0.38123 0.35884 0.32560 0.28218 0.22967 0.16894 0.10070 0.02558 -0.05588 -0.14316 -0.23584 -0.33360 -0.43626 -0.54377 -0.65615 -0.77342 -0.89549 -1.02214 -1.15305 -1.28784 -1.42604 -1.56709 -1.71022 -1.85431 -1.99775 -2.13829 -2.27343 -2.40152 -2.52304 -2.64109 -2.76053 -2.88683 -3.02519 -3.18012 -3.35516 -3.55090 -3.76327 -3.98306 -4.19989 -4.40641 -4.60026 -4.78255 -4.95561 -5.12216 +0.29704 0.32142 0.34158 0.35764 0.36950 0.37707 0.37934 0.37476 0.36154 0.33766 0.30172 0.25424 0.19653 0.12962 0.05435 -0.02857 -0.11851 -0.21492 -0.31734 -0.42547 -0.53914 -0.65833 -0.78305 -0.91327 -1.04879 -1.18932 -1.33446 -1.48374 -1.63664 -1.79259 -1.95072 -2.10962 -2.26712 -2.42026 -2.56619 -2.70394 -2.83546 -2.96535 -3.09948 -3.24382 -3.40369 -3.58361 -3.78674 -4.01243 -4.25419 -4.50066 -4.74080 -4.96812 -5.18157 -5.38301 -5.57514 -5.76104 +0.27144 0.29765 0.31946 0.33666 0.34916 0.35683 0.35884 0.35356 0.33923 0.31365 0.27482 0.22300 0.15974 0.08623 0.00344 -0.08782 -0.18684 -0.29303 -0.40591 -0.52517 -0.65069 -0.78245 -0.92044 -1.06452 -1.21443 -1.36977 -1.53007 -1.69479 -1.86345 -2.03544 -2.20971 -2.38437 -2.55642 -2.72217 -2.87900 -3.02714 -3.17017 -3.31391 -3.46509 -3.62996 -3.81384 -4.02136 -4.25516 -4.51295 -4.78563 -5.05990 -5.32441 -5.57393 -5.80861 -6.03086 -6.24376 -6.45082 +0.24428 0.27207 0.29537 0.31371 0.32686 0.33457 0.33620 0.33000 0.31430 0.28677 0.24484 0.18840 0.11919 0.03863 -0.05219 -0.15235 -0.26107 -0.37772 -0.50179 -0.63301 -0.77125 -0.91650 -1.06869 -1.22759 -1.39283 -1.56395 -1.74037 -1.92160 -2.10717 -2.29643 -2.48798 -2.67914 -2.86596 -3.04439 -3.21257 -3.37225 -3.52845 -3.68819 -3.85879 -4.04660 -4.25699 -4.49473 -4.76178 -5.05383 -5.35896 -5.66215 -5.95230 -6.22561 -6.48321 -6.72799 -6.96343 -7.19363 +0.21596 0.24474 0.26929 0.28873 0.30251 0.31023 0.31138 0.30409 0.28673 0.25695 0.21170 0.15033 0.07480 -0.01328 -0.11267 -0.22233 -0.34141 -0.46922 -0.60527 -0.74928 -0.90116 -1.06085 -1.22820 -1.40288 -1.58444 -1.77230 -1.96590 -2.16478 -2.36855 -2.57637 -2.78622 -2.99440 -3.19607 -3.38744 -3.56780 -3.74038 -3.91158 -4.08953 -4.28189 -4.49498 -4.73442 -5.00507 -5.30801 -5.63645 -5.97553 -6.30884 -6.62610 -6.92490 -7.20719 -7.47626 -7.73613 -7.99166 + + +# Thrust coefficient + +0.06742 0.06741 0.06739 0.06736 0.06732 0.06727 0.06721 0.06714 0.06706 0.06696 0.06686 0.06674 0.06662 0.06648 0.06633 0.06617 0.06600 0.06582 0.06563 0.06543 0.06522 0.06500 0.06476 0.06452 0.06427 0.06400 0.06373 0.06345 0.06315 0.06285 0.06253 0.06221 0.06188 0.06153 0.06118 0.06082 0.06045 0.06007 0.05968 0.05929 0.05888 0.05846 0.05804 0.05761 0.05717 0.05673 0.05628 0.05582 0.05535 0.05488 0.05440 0.05391 +0.07812 0.07796 0.07779 0.07760 0.07741 0.07720 0.07698 0.07675 0.07650 0.07625 0.07598 0.07571 0.07542 0.07513 0.07482 0.07450 0.07418 0.07385 0.07351 0.07316 0.07281 0.07245 0.07209 0.07172 0.07135 0.07099 0.07062 0.07025 0.06988 0.06951 0.06915 0.06880 0.06845 0.06811 0.06777 0.06744 0.06712 0.06681 0.06651 0.06622 0.06594 0.06566 0.06539 0.06513 0.06487 0.06462 0.06437 0.06412 0.06388 0.06363 0.06337 0.06311 +0.09346 0.09320 0.09295 0.09269 0.09244 0.09220 0.09197 0.09174 0.09153 0.09134 0.09116 0.09100 0.09085 0.09073 0.09062 0.09054 0.09047 0.09043 0.09040 0.09039 0.09040 0.09042 0.09045 0.09049 0.09053 0.09058 0.09062 0.09066 0.09069 0.09071 0.09070 0.09068 0.09063 0.09056 0.09045 0.09031 0.09013 0.08990 0.08964 0.08933 0.08897 0.08856 0.08811 0.08760 0.08703 0.08642 0.08575 0.08503 0.08426 0.08344 0.08257 0.08166 +0.11855 0.11879 0.11907 0.11939 0.11975 0.12013 0.12055 0.12098 0.12144 0.12190 0.12237 0.12283 0.12328 0.12371 0.12412 0.12449 0.12482 0.12510 0.12533 0.12550 0.12561 0.12564 0.12561 0.12549 0.12530 0.12502 0.12466 0.12422 0.12369 0.12307 0.12236 0.12157 0.12069 0.11973 0.11869 0.11758 0.11639 0.11513 0.11381 0.11243 0.11100 0.10950 0.10795 0.10634 0.10468 0.10297 0.10120 0.09937 0.09748 0.09554 0.09353 0.09147 +0.16154 0.16257 0.16356 0.16451 0.16541 0.16624 0.16700 0.16766 0.16823 0.16870 0.16905 0.16928 0.16940 0.16938 0.16924 0.16896 0.16855 0.16800 0.16732 0.16651 0.16557 0.16450 0.16330 0.16199 0.16057 0.15905 0.15743 0.15571 0.15391 0.15203 0.15007 0.14804 0.14593 0.14374 0.14147 0.13911 0.13666 0.13412 0.13148 0.12873 0.12586 0.12286 0.11974 0.11647 0.11307 0.10950 0.10578 0.10191 0.09789 0.09373 0.08945 0.08507 +0.21940 0.22030 0.22103 0.22158 0.22194 0.22212 0.22209 0.22187 0.22146 0.22084 0.22004 0.21904 0.21786 0.21650 0.21498 0.21330 0.21147 0.20951 0.20742 0.20522 0.20293 0.20053 0.19805 0.19548 0.19280 0.19002 0.18712 0.18409 0.18091 0.17757 0.17405 0.17035 0.16644 0.16232 0.15797 0.15337 0.14852 0.14344 0.13815 0.13265 0.12696 0.12110 0.11508 0.10891 0.10261 0.09617 0.08961 0.08293 0.07617 0.06933 0.06244 0.05549 +0.28388 0.28364 0.28314 0.28236 0.28132 0.28002 0.27849 0.27673 0.27475 0.27259 0.27024 0.26776 0.26515 0.26243 0.25962 0.25672 0.25371 0.25058 0.24731 0.24388 0.24025 0.23643 0.23236 0.22803 0.22341 0.21845 0.21312 0.20741 0.20135 0.19495 0.18823 0.18122 0.17393 0.16639 0.15861 0.15061 0.14240 0.13400 0.12544 0.11675 0.10794 0.09903 0.09004 0.08098 0.07186 0.06270 0.05350 0.04428 0.03505 0.02582 0.01659 0.00737 +0.34990 0.34797 0.34576 0.34331 0.34064 0.33782 0.33487 0.33182 0.32869 0.32548 0.32215 0.31869 0.31507 0.31124 0.30718 0.30284 0.29817 0.29309 0.28753 0.28143 0.27480 0.26767 0.26004 0.25195 0.24344 0.23455 0.22528 0.21566 0.20571 0.19550 0.18504 0.17439 0.16355 0.15255 0.14142 0.13016 0.11880 0.10734 0.09581 0.08421 0.07256 0.06086 0.04914 0.03741 0.02566 0.01393 0.00220 -0.00951 -0.02119 -0.03284 -0.04443 -0.05595 +0.41659 0.41337 0.41007 0.40673 0.40332 0.39981 0.39616 0.39233 0.38825 0.38385 0.37906 0.37373 0.36775 0.36106 0.35367 0.34557 0.33678 0.32738 0.31741 0.30687 0.29580 0.28427 0.27235 0.26009 0.24752 0.23469 0.22161 0.20832 0.19485 0.18120 0.16739 0.15345 0.13938 0.12520 0.11093 0.09659 0.08217 0.06772 0.05322 0.03871 0.02420 0.00968 -0.00482 -0.01931 -0.03377 -0.04819 -0.06255 -0.07684 -0.09102 -0.10505 -0.11890 -0.13252 +0.48931 0.48578 0.48207 0.47809 0.47374 0.46885 0.46324 0.45683 0.44955 0.44133 0.43219 0.42221 0.41139 0.39978 0.38746 0.37451 0.36102 0.34706 0.33268 0.31793 0.30284 0.28744 0.27177 0.25585 0.23969 0.22332 0.20675 0.19001 0.17311 0.15607 0.13891 0.12165 0.10430 0.08688 0.06941 0.05190 0.03437 0.01683 -0.00071 -0.01824 -0.03576 -0.05325 -0.07070 -0.08809 -0.10538 -0.12254 -0.13951 -0.15624 -0.17267 -0.18871 -0.20432 -0.21940 +0.57079 0.56550 0.55935 0.55217 0.54387 0.53445 0.52391 0.51227 0.49962 0.48609 0.47180 0.45682 0.44124 0.42511 0.40850 0.39144 0.37397 0.35614 0.33796 0.31945 0.30065 0.28158 0.26225 0.24270 0.22293 0.20298 0.18286 0.16259 0.14219 0.12168 0.10107 0.08040 0.05967 0.03890 0.01811 -0.00269 -0.02350 -0.04431 -0.06511 -0.08588 -0.10660 -0.12722 -0.14770 -0.16798 -0.18798 -0.20763 -0.22686 -0.24558 -0.26372 -0.28120 -0.29791 -0.31369 +0.64958 0.63945 0.62793 0.61515 0.60129 0.58645 0.57074 0.55423 0.53701 0.51913 0.50065 0.48162 0.46208 0.44206 0.42161 0.40075 0.37950 0.35789 0.33594 0.31369 0.29115 0.26834 0.24530 0.22203 0.19857 0.17494 0.15115 0.12723 0.10320 0.07908 0.05489 0.03065 0.00637 -0.01794 -0.04227 -0.06661 -0.09095 -0.11527 -0.13953 -0.16367 -0.18763 -0.21131 -0.23464 -0.25753 -0.27988 -0.30162 -0.32267 -0.34292 -0.36226 -0.38053 -0.39753 -0.41304 +0.71352 0.69827 0.68202 0.66483 0.64676 0.62786 0.60820 0.58782 0.56677 0.54511 0.52288 0.50010 0.47681 0.45304 0.42882 0.40417 0.37912 0.35370 0.32794 0.30185 0.27547 0.24882 0.22193 0.19482 0.16751 0.14003 0.11240 0.08466 0.05682 0.02890 0.00092 -0.02711 -0.05518 -0.08329 -0.11143 -0.13956 -0.16763 -0.19559 -0.22333 -0.25076 -0.27777 -0.30426 -0.33014 -0.35531 -0.37967 -0.40314 -0.42557 -0.44682 -0.46667 -0.48489 -0.50118 -0.51525 +0.76495 0.74631 0.72675 0.70629 0.68492 0.66269 0.63965 0.61585 0.59133 0.56613 0.54029 0.51386 0.48685 0.45932 0.43128 0.40278 0.37384 0.34450 0.31478 0.28472 0.25434 0.22367 0.19275 0.16161 0.13026 0.09875 0.06709 0.03532 0.00346 -0.02850 -0.06052 -0.09262 -0.12478 -0.15696 -0.18911 -0.22116 -0.25301 -0.28454 -0.31561 -0.34612 -0.37595 -0.40499 -0.43315 -0.46030 -0.48633 -0.51108 -0.53437 -0.55595 -0.57556 -0.59287 -0.60753 -0.61913 +0.80848 0.78721 0.76507 0.74198 0.71792 0.69285 0.66681 0.63983 0.61198 0.58332 0.55391 0.52379 0.49302 0.46164 0.42968 0.39720 0.36423 0.33080 0.29696 0.26274 0.22818 0.19330 0.15816 0.12277 0.08719 0.05143 0.01552 -0.02052 -0.05667 -0.09294 -0.12931 -0.16575 -0.20221 -0.23863 -0.27488 -0.31084 -0.34636 -0.38130 -0.41553 -0.44892 -0.48135 -0.51270 -0.54285 -0.57166 -0.59896 -0.62454 -0.64816 -0.66952 -0.68825 -0.70393 -0.71608 -0.72431 +0.84679 0.82318 0.79875 0.77338 0.74691 0.71930 0.69048 0.66049 0.62941 0.59731 0.56429 0.53044 0.49580 0.46046 0.42445 0.38783 0.35065 0.31297 0.27481 0.23624 0.19729 0.15800 0.11841 0.07858 0.03853 -0.00172 -0.04214 -0.08271 -0.12344 -0.16431 -0.20528 -0.24626 -0.28717 -0.32786 -0.36817 -0.40794 -0.44700 -0.48521 -0.52242 -0.55850 -0.59332 -0.62674 -0.65862 -0.68877 -0.71701 -0.74308 -0.76665 -0.78730 -0.80453 -0.81780 -0.82661 -0.83068 +0.88156 0.85551 0.82883 0.80125 0.77254 0.74252 0.71110 0.67824 0.64399 0.60847 0.57182 0.53414 0.49553 0.45609 0.41587 0.37495 0.33339 0.29125 0.24858 0.20544 0.16189 0.11797 0.07373 0.02921 -0.01556 -0.06055 -0.10576 -0.15117 -0.19675 -0.24246 -0.28820 -0.33384 -0.37922 -0.42415 -0.46844 -0.51191 -0.55439 -0.59572 -0.63576 -0.67436 -0.71139 -0.74668 -0.78009 -0.81141 -0.84040 -0.86669 -0.88981 -0.90918 -0.92419 -0.93423 -0.93895 -0.93825 +0.91442 0.88532 0.85606 0.82617 0.79524 0.76291 0.72898 0.69337 0.65603 0.61710 0.57675 0.53516 0.49246 0.44876 0.40417 0.35877 0.31263 0.26583 0.21845 0.17054 0.12216 0.07339 0.02425 -0.02520 -0.07495 -0.12497 -0.17526 -0.22577 -0.27644 -0.32715 -0.37777 -0.42810 -0.47793 -0.52705 -0.57524 -0.62232 -0.66810 -0.71244 -0.75519 -0.79619 -0.83531 -0.87239 -0.90726 -0.93965 -0.96919 -0.99537 -1.01751 -1.03494 -1.04697 -1.05312 -1.05319 -1.04733 +0.94638 0.91378 0.88134 0.84874 0.81543 0.78078 0.74441 0.70609 0.66574 0.62339 0.57930 0.53370 0.48678 0.43868 0.38954 0.33946 0.28855 0.23689 0.18457 0.13166 0.07824 0.02437 -0.02992 -0.08457 -0.13958 -0.19491 -0.25054 -0.30637 -0.36228 -0.41812 -0.47367 -0.52869 -0.58294 -0.63619 -0.68821 -0.73881 -0.78782 -0.83510 -0.88050 -0.92387 -0.96508 -1.00396 -1.04027 -1.07360 -1.10341 -1.12897 -1.14955 -1.16439 -1.17284 -1.17457 -1.16960 -1.15850 +0.97776 0.94146 0.90544 0.86965 0.83356 0.79645 0.75760 0.71662 0.67328 0.62754 0.57965 0.52994 0.47865 0.42599 0.37212 0.31718 0.26128 0.20454 0.14707 0.08894 0.03023 -0.02900 -0.08869 -0.14882 -0.20937 -0.27027 -0.33145 -0.39277 -0.45406 -0.51509 -0.57560 -0.63531 -0.69396 -0.75129 -0.80708 -0.86116 -0.91339 -0.96361 -1.01169 -1.05749 -1.10087 -1.14158 -1.17923 -1.21325 -1.24289 -1.26735 -1.28582 -1.29752 -1.30190 -1.29881 -1.28861 -1.27230 +1.00869 0.96856 0.92879 0.88940 0.85015 0.81026 0.76882 0.72514 0.67882 0.62969 0.57794 0.52400 0.46821 0.41081 0.35203 0.29201 0.23093 0.16889 0.10603 0.04244 -0.02180 -0.08663 -0.15201 -0.21789 -0.28422 -0.35091 -0.41784 -0.48480 -0.55156 -0.61783 -0.68332 -0.74771 -0.81072 -0.87211 -0.93168 -0.98928 -1.04477 -1.09801 -1.14889 -1.19724 -1.24285 -1.28532 -1.32411 -1.35847 -1.38754 -1.41045 -1.42633 -1.43442 -1.43431 -1.42611 -1.41063 -1.38920 +1.03929 0.99521 0.95150 0.90834 0.86555 0.82255 0.77828 0.73181 0.68249 0.62995 0.57429 0.51601 0.45556 0.39325 0.32936 0.26407 0.19758 0.13003 0.06155 -0.00774 -0.07777 -0.14848 -0.21980 -0.29168 -0.36403 -0.43672 -0.50956 -0.58227 -0.65458 -0.72614 -0.79662 -0.86569 -0.93308 -0.99856 -1.06198 -1.12318 -1.18205 -1.23846 -1.29227 -1.34326 -1.39107 -1.43516 -1.47483 -1.50920 -1.53733 -1.55829 -1.57115 -1.57521 -1.57025 -1.55677 -1.53600 -1.50960 +1.06966 1.02148 0.97370 0.92660 0.88002 0.83361 0.78622 0.73679 0.68441 0.62843 0.56880 0.50606 0.44079 0.37340 0.30420 0.23343 0.16131 0.08802 0.01369 -0.06156 -0.13763 -0.21447 -0.29199 -0.37012 -0.44871 -0.52758 -0.60646 -0.68503 -0.76295 -0.83985 -0.91535 -0.98913 -1.06095 -1.13063 -1.19800 -1.26295 -1.32536 -1.38512 -1.44197 -1.49561 -1.54552 -1.59105 -1.63134 -1.66542 -1.69229 -1.71092 -1.72034 -1.71998 -1.70990 -1.69106 -1.66502 -1.63378 +1.09984 1.04744 0.99545 0.94426 0.89372 0.84363 0.79288 0.74027 0.68470 0.62523 0.56155 0.49423 0.42399 0.35133 0.27662 0.20016 0.12220 0.04292 -0.03750 -0.11895 -0.20134 -0.28456 -0.36853 -0.45313 -0.53816 -0.62337 -0.70842 -0.79294 -0.87655 -0.95882 -1.03940 -1.11798 -1.19435 -1.26835 -1.33983 -1.40872 -1.47487 -1.53809 -1.59804 -1.65427 -1.70618 -1.75296 -1.79364 -1.82717 -1.85244 -1.86835 -1.87394 -1.86882 -1.85345 -1.82918 -1.79794 -1.76199 +1.12984 1.07314 1.01682 0.96138 0.90674 0.85277 0.79840 0.74237 0.68346 0.62041 0.55262 0.48060 0.40522 0.32710 0.24668 0.16432 0.08028 -0.00521 -0.09198 -0.17989 -0.26883 -0.35869 -0.44935 -0.54064 -0.63230 -0.72399 -0.81533 -0.90590 -0.99526 -1.08299 -1.16874 -1.25224 -1.33331 -1.41180 -1.48760 -1.56062 -1.63067 -1.69744 -1.76047 -1.81924 -1.87301 -1.92086 -1.96173 -1.99444 -2.01781 -2.03062 -2.03202 -2.02186 -2.00106 -1.97133 -1.93492 -1.89440 +1.15951 1.09859 1.03782 0.97800 0.91913 0.86109 0.80291 0.74325 0.68078 0.61407 0.54209 0.46522 0.38454 0.30077 0.21444 0.12595 0.03561 -0.05634 -0.14970 -0.24432 -0.34007 -0.43682 -0.53440 -0.63259 -0.73103 -0.82935 -0.92709 -1.02381 -1.11903 -1.21232 -1.30338 -1.39197 -1.47791 -1.56108 -1.64142 -1.71876 -1.79281 -1.86315 -1.92926 -1.99048 -2.04600 -2.09478 -2.13563 -2.16727 -2.18839 -2.19775 -2.19462 -2.17922 -2.15287 -2.11765 -2.07612 -2.03113 +1.18862 1.12373 1.05850 0.99416 0.93093 0.86866 0.80651 0.74299 0.67677 0.60626 0.52999 0.44816 0.36200 0.27239 0.17993 0.08509 -0.01179 -0.11043 -0.21063 -0.31222 -0.41502 -0.51890 -0.62363 -0.72890 -0.83429 -0.93937 -1.04366 -1.14664 -1.24783 -1.34683 -1.44336 -1.53720 -1.62821 -1.71631 -1.80138 -1.88318 -1.96131 -2.03524 -2.10438 -2.16801 -2.22517 -2.27473 -2.31535 -2.34563 -2.36418 -2.36975 -2.36181 -2.34099 -2.30900 -2.26827 -2.22163 -2.17230 +1.21694 1.14839 1.07885 1.00990 0.94219 0.87554 0.80925 0.74168 0.67151 0.59704 0.51639 0.42945 0.33764 0.24199 0.14319 0.04178 -0.06187 -0.16746 -0.27475 -0.38354 -0.49366 -0.60490 -0.71699 -0.82952 -0.94203 -1.05403 -1.16498 -1.27435 -1.38166 -1.48653 -1.58871 -1.68801 -1.78432 -1.87756 -1.96754 -2.05390 -2.13615 -2.21368 -2.28584 -2.35180 -2.41052 -2.46070 -2.50088 -2.52955 -2.54521 -2.54667 -2.53367 -2.50727 -2.46954 -2.42325 -2.37156 -2.31804 +1.24397 1.17246 1.09881 1.02523 0.95292 0.88177 0.81120 0.73941 0.66507 0.58646 0.50132 0.40914 0.31150 0.20960 0.10425 -0.00396 -0.11462 -0.22739 -0.34202 -0.45827 -0.57595 -0.69479 -0.81444 -0.93441 -1.05421 -1.17327 -1.29104 -1.40695 -1.52054 -1.63147 -1.73950 -1.84447 -1.94631 -2.04489 -2.13991 -2.23092 -2.31732 -2.39846 -2.47362 -2.54187 -2.60205 -2.65269 -2.69222 -2.71901 -2.73147 -2.72853 -2.71026 -2.67812 -2.63458 -2.58267 -2.52599 -2.46851 + + +# Torque coefficient + +0.00384 0.00412 0.00441 0.00469 0.00497 0.00525 0.00553 0.00581 0.00609 0.00636 0.00664 0.00691 0.00718 0.00744 0.00771 0.00797 0.00823 0.00849 0.00874 0.00899 0.00924 0.00949 0.00973 0.00998 0.01021 0.01045 0.01068 0.01091 0.01114 0.01136 0.01158 0.01179 0.01201 0.01222 0.01242 0.01263 0.01283 0.01302 0.01321 0.01340 0.01359 0.01377 0.01395 0.01413 0.01430 0.01447 0.01464 0.01481 0.01497 0.01514 0.01530 0.01546 +0.00416 0.00448 0.00481 0.00513 0.00545 0.00576 0.00608 0.00639 0.00670 0.00701 0.00731 0.00762 0.00792 0.00822 0.00851 0.00881 0.00911 0.00940 0.00969 0.00999 0.01028 0.01058 0.01088 0.01118 0.01148 0.01179 0.01210 0.01242 0.01274 0.01307 0.01341 0.01376 0.01411 0.01448 0.01486 0.01525 0.01565 0.01607 0.01649 0.01693 0.01739 0.01785 0.01833 0.01882 0.01932 0.01983 0.02035 0.02088 0.02141 0.02195 0.02249 0.02304 +0.00496 0.00541 0.00587 0.00634 0.00682 0.00730 0.00779 0.00829 0.00880 0.00933 0.00987 0.01042 0.01098 0.01157 0.01216 0.01278 0.01341 0.01405 0.01471 0.01539 0.01608 0.01679 0.01751 0.01824 0.01898 0.01973 0.02048 0.02124 0.02200 0.02276 0.02351 0.02426 0.02500 0.02573 0.02644 0.02714 0.02782 0.02848 0.02911 0.02972 0.03030 0.03085 0.03136 0.03184 0.03228 0.03269 0.03305 0.03337 0.03365 0.03389 0.03408 0.03423 +0.00864 0.00952 0.01042 0.01135 0.01229 0.01326 0.01425 0.01525 0.01626 0.01729 0.01833 0.01937 0.02042 0.02146 0.02250 0.02353 0.02456 0.02557 0.02656 0.02753 0.02848 0.02940 0.03029 0.03115 0.03198 0.03277 0.03351 0.03422 0.03488 0.03549 0.03605 0.03656 0.03702 0.03742 0.03776 0.03805 0.03828 0.03845 0.03857 0.03863 0.03863 0.03857 0.03845 0.03828 0.03806 0.03778 0.03745 0.03707 0.03665 0.03617 0.03566 0.03510 +0.01705 0.01845 0.01984 0.02122 0.02260 0.02396 0.02530 0.02662 0.02791 0.02917 0.03040 0.03159 0.03274 0.03385 0.03491 0.03592 0.03688 0.03779 0.03864 0.03942 0.04014 0.04080 0.04138 0.04189 0.04233 0.04270 0.04299 0.04321 0.04335 0.04342 0.04341 0.04334 0.04319 0.04297 0.04269 0.04235 0.04194 0.04148 0.04096 0.04038 0.03973 0.03903 0.03825 0.03741 0.03650 0.03551 0.03444 0.03330 0.03209 0.03081 0.02946 0.02806 +0.02777 0.02938 0.03095 0.03248 0.03396 0.03538 0.03675 0.03806 0.03931 0.04049 0.04161 0.04265 0.04362 0.04450 0.04530 0.04601 0.04663 0.04716 0.04760 0.04795 0.04820 0.04836 0.04843 0.04842 0.04831 0.04813 0.04786 0.04751 0.04709 0.04659 0.04601 0.04535 0.04461 0.04378 0.04287 0.04185 0.04075 0.03954 0.03825 0.03687 0.03541 0.03387 0.03225 0.03056 0.02879 0.02696 0.02507 0.02311 0.02111 0.01905 0.01696 0.01483 +0.03810 0.03974 0.04130 0.04278 0.04419 0.04551 0.04675 0.04789 0.04894 0.04988 0.05071 0.05143 0.05204 0.05255 0.05295 0.05324 0.05343 0.05350 0.05346 0.05332 0.05307 0.05272 0.05227 0.05172 0.05107 0.05031 0.04944 0.04844 0.04732 0.04610 0.04476 0.04332 0.04177 0.04013 0.03839 0.03655 0.03462 0.03261 0.03053 0.02838 0.02617 0.02391 0.02159 0.01923 0.01684 0.01440 0.01194 0.00944 0.00692 0.00437 0.00181 -0.00078 +0.04723 0.04880 0.05027 0.05163 0.05287 0.05400 0.05501 0.05590 0.05666 0.05730 0.05781 0.05818 0.05842 0.05851 0.05846 0.05828 0.05796 0.05751 0.05691 0.05617 0.05528 0.05426 0.05310 0.05181 0.05039 0.04885 0.04719 0.04540 0.04351 0.04151 0.03942 0.03725 0.03499 0.03266 0.03025 0.02778 0.02526 0.02267 0.02004 0.01737 0.01465 0.01189 0.00910 0.00627 0.00342 0.00054 -0.00238 -0.00532 -0.00828 -0.01126 -0.01426 -0.01726 +0.05515 0.05664 0.05800 0.05923 0.06032 0.06125 0.06202 0.06262 0.06304 0.06327 0.06332 0.06316 0.06281 0.06227 0.06156 0.06068 0.05964 0.05845 0.05712 0.05563 0.05401 0.05226 0.05038 0.04840 0.04632 0.04413 0.04185 0.03948 0.03702 0.03447 0.03185 0.02915 0.02639 0.02355 0.02066 0.01772 0.01472 0.01168 0.00860 0.00548 0.00233 -0.00086 -0.00409 -0.00736 -0.01066 -0.01400 -0.01736 -0.02073 -0.02412 -0.02750 -0.03086 -0.03420 +0.06239 0.06379 0.06501 0.06600 0.06676 0.06726 0.06748 0.06745 0.06717 0.06665 0.06594 0.06504 0.06396 0.06272 0.06132 0.05978 0.05811 0.05631 0.05440 0.05238 0.05025 0.04801 0.04566 0.04321 0.04066 0.03801 0.03527 0.03243 0.02951 0.02650 0.02342 0.02027 0.01705 0.01379 0.01046 0.00709 0.00368 0.00022 -0.00329 -0.00684 -0.01044 -0.01409 -0.01779 -0.02153 -0.02530 -0.02909 -0.03286 -0.03662 -0.04033 -0.04399 -0.04759 -0.05115 +0.06860 0.06955 0.07017 0.07045 0.07042 0.07010 0.06954 0.06875 0.06777 0.06663 0.06535 0.06393 0.06237 0.06069 0.05889 0.05696 0.05492 0.05276 0.05048 0.04809 0.04557 0.04294 0.04019 0.03733 0.03436 0.03129 0.02812 0.02485 0.02151 0.01808 0.01458 0.01102 0.00739 0.00371 -0.00002 -0.00381 -0.00766 -0.01157 -0.01555 -0.01959 -0.02369 -0.02784 -0.03203 -0.03623 -0.04041 -0.04454 -0.04861 -0.05261 -0.05652 -0.06038 -0.06420 -0.06805 +0.07147 0.07161 0.07143 0.07098 0.07031 0.06948 0.06849 0.06736 0.06609 0.06469 0.06315 0.06148 0.05968 0.05775 0.05568 0.05349 0.05116 0.04869 0.04609 0.04336 0.04049 0.03749 0.03437 0.03112 0.02775 0.02428 0.02070 0.01703 0.01328 0.00945 0.00554 0.00157 -0.00247 -0.00658 -0.01077 -0.01502 -0.01936 -0.02378 -0.02827 -0.03284 -0.03745 -0.04207 -0.04668 -0.05123 -0.05569 -0.06005 -0.06431 -0.06849 -0.07261 -0.07675 -0.08097 -0.08531 +0.07016 0.06992 0.06949 0.06890 0.06814 0.06723 0.06617 0.06495 0.06358 0.06206 0.06039 0.05858 0.05660 0.05448 0.05220 0.04977 0.04717 0.04442 0.04151 0.03845 0.03523 0.03187 0.02836 0.02473 0.02097 0.01710 0.01312 0.00905 0.00489 0.00065 -0.00368 -0.00809 -0.01258 -0.01716 -0.02184 -0.02662 -0.03149 -0.03645 -0.04148 -0.04654 -0.05159 -0.05660 -0.06150 -0.06629 -0.07094 -0.07548 -0.07992 -0.08436 -0.08886 -0.09351 -0.09836 -0.10339 +0.06663 0.06654 0.06627 0.06583 0.06519 0.06437 0.06336 0.06217 0.06079 0.05922 0.05748 0.05555 0.05343 0.05113 0.04865 0.04597 0.04311 0.04006 0.03683 0.03343 0.02986 0.02612 0.02224 0.01822 0.01407 0.00979 0.00542 0.00093 -0.00365 -0.00833 -0.01310 -0.01799 -0.02298 -0.02809 -0.03331 -0.03864 -0.04407 -0.04956 -0.05507 -0.06056 -0.06597 -0.07124 -0.07636 -0.08132 -0.08614 -0.09089 -0.09567 -0.10057 -0.10569 -0.11109 -0.11674 -0.12259 +0.06227 0.06251 0.06255 0.06237 0.06196 0.06132 0.06043 0.05931 0.05795 0.05637 0.05456 0.05252 0.05026 0.04777 0.04507 0.04214 0.03900 0.03564 0.03208 0.02833 0.02439 0.02029 0.01602 0.01160 0.00705 0.00237 -0.00243 -0.00734 -0.01237 -0.01751 -0.02279 -0.02819 -0.03373 -0.03939 -0.04518 -0.05107 -0.05703 -0.06300 -0.06894 -0.07477 -0.08044 -0.08592 -0.09121 -0.09635 -0.10144 -0.10658 -0.11189 -0.11749 -0.12346 -0.12978 -0.13638 -0.14307 +0.05771 0.05829 0.05866 0.05879 0.05864 0.05821 0.05748 0.05646 0.05514 0.05353 0.05165 0.04950 0.04708 0.04440 0.04146 0.03827 0.03484 0.03116 0.02727 0.02316 0.01885 0.01436 0.00970 0.00489 -0.00008 -0.00518 -0.01041 -0.01578 -0.02129 -0.02695 -0.03276 -0.03872 -0.04483 -0.05107 -0.05743 -0.06386 -0.07032 -0.07673 -0.08301 -0.08910 -0.09497 -0.10063 -0.10613 -0.11158 -0.11710 -0.12282 -0.12889 -0.13542 -0.14243 -0.14980 -0.15735 -0.16480 +0.05320 0.05408 0.05476 0.05518 0.05530 0.05509 0.05453 0.05362 0.05234 0.05072 0.04877 0.04650 0.04391 0.04103 0.03784 0.03438 0.03064 0.02664 0.02240 0.01793 0.01324 0.00836 0.00330 -0.00193 -0.00732 -0.01287 -0.01857 -0.02444 -0.03047 -0.03667 -0.04305 -0.04959 -0.05629 -0.06311 -0.07003 -0.07697 -0.08388 -0.09066 -0.09722 -0.10353 -0.10960 -0.11550 -0.12133 -0.12723 -0.13334 -0.13985 -0.14691 -0.15457 -0.16275 -0.17121 -0.17960 -0.18762 +0.04896 0.05002 0.05093 0.05160 0.05197 0.05198 0.05159 0.05079 0.04957 0.04793 0.04590 0.04350 0.04074 0.03764 0.03420 0.03045 0.02640 0.02207 0.01747 0.01263 0.00756 0.00228 -0.00320 -0.00887 -0.01471 -0.02073 -0.02693 -0.03332 -0.03991 -0.04669 -0.05366 -0.06080 -0.06809 -0.07549 -0.08294 -0.09037 -0.09767 -0.10476 -0.11157 -0.11812 -0.12446 -0.13069 -0.13697 -0.14345 -0.15035 -0.15787 -0.16614 -0.17510 -0.18449 -0.19391 -0.20296 -0.21142 +0.04506 0.04623 0.04726 0.04811 0.04869 0.04889 0.04867 0.04798 0.04681 0.04516 0.04305 0.04052 0.03757 0.03424 0.03054 0.02650 0.02213 0.01745 0.01249 0.00727 0.00179 -0.00390 -0.00981 -0.01593 -0.02225 -0.02877 -0.03551 -0.04247 -0.04964 -0.05702 -0.06459 -0.07234 -0.08023 -0.08819 -0.09616 -0.10402 -0.11168 -0.11905 -0.12614 -0.13297 -0.13964 -0.14630 -0.15314 -0.16039 -0.16831 -0.17710 -0.18675 -0.19704 -0.20752 -0.21772 -0.22733 -0.23625 +0.04142 0.04269 0.04381 0.04476 0.04547 0.04584 0.04577 0.04519 0.04407 0.04241 0.04021 0.03754 0.03440 0.03083 0.02687 0.02252 0.01782 0.01279 0.00745 0.00183 -0.00405 -0.01018 -0.01655 -0.02314 -0.02996 -0.03702 -0.04433 -0.05187 -0.05965 -0.06765 -0.07585 -0.08421 -0.09269 -0.10120 -0.10965 -0.11793 -0.12593 -0.13362 -0.14100 -0.14816 -0.15523 -0.16241 -0.16998 -0.17822 -0.18742 -0.19764 -0.20874 -0.22027 -0.23169 -0.24257 -0.25272 -0.26218 +0.03800 0.03937 0.04056 0.04157 0.04237 0.04285 0.04290 0.04242 0.04135 0.03966 0.03738 0.03456 0.03122 0.02741 0.02317 0.01851 0.01347 0.00807 0.00235 -0.00368 -0.01000 -0.01658 -0.02342 -0.03051 -0.03787 -0.04550 -0.05340 -0.06156 -0.06996 -0.07860 -0.08743 -0.09641 -0.10547 -0.11451 -0.12344 -0.13212 -0.14048 -0.14850 -0.15620 -0.16372 -0.17127 -0.17914 -0.18765 -0.19714 -0.20778 -0.21952 -0.23201 -0.24465 -0.25692 -0.26845 -0.27921 -0.28929 +0.03474 0.03622 0.03748 0.03855 0.03939 0.03993 0.04006 0.03966 0.03863 0.03693 0.03456 0.03158 0.02804 0.02398 0.01944 0.01446 0.00907 0.00329 -0.00283 -0.00929 -0.01605 -0.02310 -0.03044 -0.03807 -0.04599 -0.05421 -0.06273 -0.07152 -0.08057 -0.08985 -0.09932 -0.10891 -0.11856 -0.12814 -0.13755 -0.14665 -0.15537 -0.16371 -0.17174 -0.17970 -0.18788 -0.19663 -0.20631 -0.21721 -0.22939 -0.24265 -0.25645 -0.27013 -0.28319 -0.29540 -0.30683 -0.31762 +0.03162 0.03320 0.03454 0.03565 0.03652 0.03710 0.03728 0.03692 0.03592 0.03420 0.03173 0.02859 0.02484 0.02052 0.01569 0.01037 0.00462 -0.00155 -0.00809 -0.01499 -0.02221 -0.02976 -0.03762 -0.04581 -0.05433 -0.06317 -0.07233 -0.08177 -0.09148 -0.10141 -0.11153 -0.12175 -0.13199 -0.14212 -0.15201 -0.16153 -0.17059 -0.17925 -0.18768 -0.19620 -0.20518 -0.21502 -0.22603 -0.23845 -0.25223 -0.26698 -0.28201 -0.29666 -0.31050 -0.32345 -0.33562 -0.34720 +0.02862 0.03030 0.03171 0.03287 0.03375 0.03434 0.03454 0.03421 0.03322 0.03147 0.02891 0.02560 0.02162 0.01704 0.01190 0.00624 0.00010 -0.00647 -0.01344 -0.02079 -0.02850 -0.03657 -0.04499 -0.05377 -0.06290 -0.07238 -0.08219 -0.09230 -0.10268 -0.11329 -0.12406 -0.13493 -0.14579 -0.15648 -0.16685 -0.17675 -0.18614 -0.19515 -0.20409 -0.21333 -0.22329 -0.23435 -0.24682 -0.26084 -0.27623 -0.29242 -0.30864 -0.32423 -0.33889 -0.35263 -0.36562 -0.37804 +0.02570 0.02749 0.02897 0.03017 0.03107 0.03166 0.03185 0.03152 0.03053 0.02873 0.02607 0.02260 0.01839 0.01353 0.00806 0.00205 -0.00447 -0.01146 -0.01889 -0.02671 -0.03493 -0.04354 -0.05254 -0.06193 -0.07171 -0.08185 -0.09233 -0.10313 -0.11419 -0.12549 -0.13695 -0.14849 -0.15997 -0.17123 -0.18205 -0.19230 -0.20204 -0.21149 -0.22105 -0.23117 -0.24225 -0.25465 -0.26867 -0.28434 -0.30135 -0.31895 -0.33631 -0.35285 -0.36837 -0.38297 -0.39683 -0.41016 +0.02287 0.02475 0.02630 0.02754 0.02845 0.02903 0.02921 0.02885 0.02784 0.02600 0.02323 0.01958 0.01513 0.00998 0.00418 -0.00220 -0.00912 -0.01655 -0.02443 -0.03276 -0.04151 -0.05069 -0.06029 -0.07032 -0.08075 -0.09157 -0.10275 -0.11424 -0.12602 -0.13802 -0.15020 -0.16243 -0.17456 -0.18635 -0.19759 -0.20819 -0.21832 -0.22832 -0.23865 -0.24976 -0.26207 -0.27592 -0.29157 -0.30894 -0.32756 -0.34653 -0.36502 -0.38253 -0.39896 -0.41447 -0.42927 -0.44358 +0.02013 0.02207 0.02369 0.02496 0.02589 0.02646 0.02661 0.02621 0.02515 0.02326 0.02038 0.01653 0.01184 0.00639 0.00025 -0.00651 -0.01385 -0.02173 -0.03010 -0.03894 -0.04825 -0.05801 -0.06825 -0.07893 -0.09004 -0.10156 -0.11345 -0.12566 -0.13817 -0.15092 -0.16384 -0.17679 -0.18954 -0.20183 -0.21346 -0.22445 -0.23505 -0.24571 -0.25692 -0.26914 -0.28278 -0.29816 -0.31550 -0.33461 -0.35483 -0.37516 -0.39478 -0.41328 -0.43068 -0.44716 -0.46294 -0.47829 +0.01747 0.01945 0.02112 0.02243 0.02337 0.02392 0.02404 0.02359 0.02247 0.02050 0.01751 0.01347 0.00852 0.00276 -0.00373 -0.01089 -0.01867 -0.02701 -0.03588 -0.04526 -0.05514 -0.06553 -0.07641 -0.08777 -0.09958 -0.11182 -0.12443 -0.13739 -0.15066 -0.16419 -0.17788 -0.19155 -0.20491 -0.21766 -0.22969 -0.24110 -0.25227 -0.26369 -0.27589 -0.28932 -0.30436 -0.32136 -0.34045 -0.36133 -0.38315 -0.40482 -0.42557 -0.44511 -0.46353 -0.48103 -0.49786 -0.51432 +0.01491 0.01689 0.01859 0.01993 0.02088 0.02142 0.02150 0.02099 0.01979 0.01774 0.01461 0.01038 0.00516 -0.00092 -0.00778 -0.01535 -0.02357 -0.03239 -0.04178 -0.05172 -0.06221 -0.07323 -0.08478 -0.09684 -0.10938 -0.12234 -0.13571 -0.14944 -0.16350 -0.17785 -0.19234 -0.20671 -0.22063 -0.23384 -0.24629 -0.25820 -0.27002 -0.28231 -0.29558 -0.31029 -0.32682 -0.34551 -0.36642 -0.38909 -0.41250 -0.43551 -0.45741 -0.47803 -0.49752 -0.51610 -0.53403 -0.55167 + diff --git a/Tune_Cases/DISCON.IN b/Tune_Cases/DISCON.IN new file mode 100644 index 000000000..1684aa6dd --- /dev/null +++ b/Tune_Cases/DISCON.IN @@ -0,0 +1,103 @@ +! Controller parameter input file for the 5MW_Land wind turbine +! - File written using NREL Baseline Controller tuning logic on 10/02/19 + +!------- DEBUG ------------------------------------------------------------ +1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file + +!------- CONTROLLER FLAGS ------------------------------------------------- +1 ! F_LPFType - {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) +0 ! F_NotchType - Notch on the measured generator speed {0: disable, 1: enable} +0 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} +2 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} +1 ! PC_ControlMode - Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} +0 ! Y_ControlMode - Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} +1 ! SS_Mode - Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} +2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Imersion and Invariance Estimator (Ortega et al.)} +1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} + +!------- FILTERS ---------------------------------------------------------- +4.630253480546613 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] +0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] +0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0.5 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [Hz]. + +!------- BLADE PITCH CONTROL ---------------------------------------------- +136 ! PC_GS_n - Amount of gain-scheduling table entries +0. 0.02213546 0.03529397 0.04532979 0.05390455 0.06152115 0.06834772 0.07463941 0.0805748 0.0861644 0.09140002 0.09649561 0.10126524 0.10593769 0.11038267 0.11473751 0.11890645 0.12302122 0.12695386 0.13088595 0.13461563 0.13834687 0.14196041 0.14551431 0.14903823 0.1524332 0.15583161 0.15913855 0.16239386 0.16565304 0.16878668 0.1719182 0.17503408 0.17805189 0.18107507 0.18407263 0.18699401 0.18992101 0.1928231 0.19565677 0.1984955 0.20131828 0.20407024 0.2068263 0.20958195 0.21225736 0.21493607 0.21761843 0.2202399 0.22284822 0.22546056 0.22804367 0.23058995 0.2331405 0.2356938 0.23818454 0.2406792 0.2431782 0.24564725 0.24808951 0.25053514 0.25298442 0.25537868 0.25777304 0.26016986 0.2625513 0.2648963 0.26724271 0.26959085 0.27190982 0.27420946 0.27651057 0.27881363 0.28108029 0.28333948 0.28560068 0.28786443 0.29008857 0.29231251 0.29453891 0.29676708 0.29895701 0.30114904 0.30334354 0.30553887 0.30769817 0.30985921 0.31202215 0.31418655 0.31631398 0.31844196 0.32057064 0.32270018 0.32479655 0.32688959 0.32898275 0.33107635 0.33314453 0.33520364 0.33726287 0.33932258 0.34136653 0.34339459 0.34542303 0.34745227 0.34947646 0.35147715 0.35347864 0.35548136 0.35748577 0.35946701 0.36144502 0.36342469 0.36540647 0.36737816 0.36933562 0.37129481 0.37325592 0.37521913 0.37715585 0.37909299 0.38103103 0.38297013 0.38489667 0.38680872 0.38872069 0.39063275 0.39254504 0.39443197 0.39631595 0.39819934 0.40008235 0.40195758 0.40381318 0.4056679 0.40752199 ! PC_GS_angles - Gain-schedule table: pitch angles +-0.02253679 -0.02175039 -0.02101063 -0.02031347 -0.01965535 -0.01903307 -0.01844378 -0.01788493 -0.01735422 -0.01684957 -0.01636911 -0.01591114 -0.01547412 -0.01505665 -0.01465744 -0.01427531 -0.0139092 -0.01355812 -0.01322116 -0.01289748 -0.01258633 -0.01228697 -0.01199876 -0.01172108 -0.01145337 -0.0111951 -0.01094578 -0.01070495 -0.01047218 -0.01024708 -0.01002927 -0.00981841 -0.00961417 -0.00941624 -0.00922433 -0.00903818 -0.00885752 -0.00868212 -0.00851175 -0.0083462 -0.00818526 -0.00802875 -0.00787649 -0.0077283 -0.00758403 -0.00744352 -0.00730662 -0.0071732 -0.00704313 -0.00691628 -0.00679253 -0.00667178 -0.00655391 -0.00643882 -0.00632642 -0.00621662 -0.00610931 -0.00600442 -0.00590187 -0.00580159 -0.00570349 -0.0056075 -0.00551356 -0.00542161 -0.00533158 -0.00524341 -0.00515704 -0.00507243 -0.00498951 -0.00490824 -0.00482856 -0.00475044 -0.00467382 -0.00459867 -0.00452493 -0.00445258 -0.00438158 -0.00431188 -0.00424344 -0.00417625 -0.00411026 -0.00404544 -0.00398176 -0.00391919 -0.0038577 -0.00379726 -0.00373785 -0.00367945 -0.00362201 -0.00356553 -0.00350998 -0.00345533 -0.00340157 -0.00334867 -0.00329661 -0.00324537 -0.00319493 -0.00314528 -0.00309639 -0.00304825 -0.00300084 -0.00295415 -0.00290815 -0.00286284 -0.0028182 -0.0027742 -0.00273085 -0.00268812 -0.00264601 -0.00260449 -0.00256356 -0.0025232 -0.0024834 -0.00244415 -0.00240545 -0.00236727 -0.0023296 -0.00229245 -0.00225578 -0.00221961 -0.00218391 -0.00214868 -0.00211391 -0.00207959 -0.00204571 -0.00201226 -0.00197923 -0.00194663 -0.00191443 -0.00188263 -0.00185122 -0.0018202 -0.00178956 -0.00175929 -0.00172938 -0.00169984 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-0.00978033 -0.00948145 -0.00920029 -0.00893533 -0.0086852 -0.00844869 -0.00822472 -0.00801232 -0.00781062 -0.00761882 -0.00743621 -0.00726216 -0.00709606 -0.00693739 -0.00678566 -0.00664043 -0.00650129 -0.00636785 -0.00623979 -0.00611677 -0.00599851 -0.00588473 -0.00577519 -0.00566966 -0.00556791 -0.00546975 -0.00537499 -0.00528346 -0.00519499 -0.00510944 -0.00502666 -0.00494652 -0.00486889 -0.00479367 -0.00472073 -0.00464998 -0.00458132 -0.00451465 -0.0044499 -0.00438698 -0.00432582 -0.00426633 -0.00420846 -0.00415214 -0.00409731 -0.0040439 -0.00399187 -0.00394117 -0.00389173 -0.00384352 -0.00379649 -0.00375059 -0.0037058 -0.00366206 -0.00361934 -0.0035776 -0.00353682 -0.00349695 -0.00345798 -0.00341986 -0.00338258 -0.0033461 -0.0033104 -0.00327545 -0.00324123 -0.00320772 -0.00317489 -0.00314273 -0.00311122 -0.00308033 -0.00305005 -0.00302036 -0.00299124 -0.00296267 -0.00293465 -0.00290715 -0.00288017 -0.00285368 -0.00282767 -0.00280213 -0.00277705 -0.00275241 -0.00272821 -0.00270443 -0.00268106 -0.00265809 -0.00263551 -0.00261331 -0.00259148 -0.00257002 -0.0025489 -0.00252813 -0.0025077 -0.00248759 -0.00246781 -0.00244833 -0.00242916 -0.00241029 -0.00239171 -0.00237342 -0.0023554 -0.00233765 -0.00232017 -0.00230295 -0.00228598 -0.00226926 -0.00225278 -0.00223654 -0.00222054 -0.00220476 -0.0021892 -0.00217386 -0.00215874 -0.00214382 -0.00212911 -0.0021146 -0.00210028 -0.00208616 -0.00207223 -0.00205848 -0.00204491 -0.00203152 -0.00201831 -0.00200526 -0.00199238 -0.00197967 -0.00196712 -0.00195473 -0.00194249 -0.0019304 -0.00191847 -0.00190668 -0.00189503 -0.00188353 -0.00187216 -0.00186093 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. +-0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. +122.90957658394467 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] +0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] +0.0349066 ! Z_PitchAmplitude - Amplitude of sine pitch excitation, [rad] +0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] + +!------- INDIVIDUAL PITCH CONTROL ----------------------------------------- +0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] + +!------- VS TORQUE CONTROL ------------------------------------------------ +100.0 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +40680.312624664395 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +44748.34388713084 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. +0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5000000 ! VS_RtPwr - Wind turbine rated power [W] +40680.312624664395 ! VS_RtTq - Rated torque, [Nm]. +122.90957658394467 ! VS_RefSpd - Rated generator speed [rad/s] +1 ! VS_n - Number of generator PI torque controller gains +-1545.1137906906267 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-387.1039217727707 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) + +!------- SETPOINT SMOOTHER --------------------------------------------- +30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. +0.001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. + +!------- WIND SPEED ESTIMATOR --------------------------------------------- +63.0 ! WE_BladeRadius - Blade length [m] +4 ! WE_CP_n - Amount of parameters in the Cp array +0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +40469564.444 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +1.225 ! WE_RhoAir - Air density, [kg m^-3] +"Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) +52 29 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +210 ! WE_FOPoles_N - Number of first-order system poles used in EKF + 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02151068 -0.02204845 -0.02258622 -0.02312398 -0.02366175 -0.02419952 -0.02473728 -0.02527505 -0.02581282 -0.02635059 -0.02688835 -0.02742612 -0.02796389 -0.02850165 -0.02903942 -0.02957719 -0.03011495 -0.03065272 -0.03119049 -0.03172826 -0.03226602 -0.03280379 -0.03334156 -0.03387932 -0.03441709 -0.03495486 -0.03549263 -0.03603039 -0.03656816 -0.03710593 -0.03764369 -0.03818146 -0.03871923 -0.03925699 -0.03979476 -0.04033253 -0.0408703 -0.04140806 -0.04194583 -0.0424836 -0.04302136 -0.04355913 -0.0440969 -0.04463467 -0.04517243 -0.0457102 -0.04624797 -0.04678573 -0.0473235 -0.04786127 -0.04839903 -0.0489368 -0.04947457 -0.05001234 -0.0505501 -0.05108787 -0.05162564 -0.0521634 -0.05270117 -0.05323894 -0.05377671 -0.05431447 -0.05485224 -0.05539001 -0.05592777 -0.05646554 -0.05700331 -0.05754107 -0.05807884 -0.05861661 -0.05915438 -0.05969214 -0.06022991 -0.06076768 -0.05963612 -0.05145035 -0.04909405 -0.0485834 -0.04902569 -0.05005874 -0.05144802 -0.05311374 -0.05502931 -0.05711571 -0.05929327 -0.06166595 -0.06405049 -0.06660033 -0.06917487 -0.07187559 -0.07458689 -0.07742473 -0.08023317 -0.08319769 -0.08606723 -0.08906988 -0.09205042 -0.09507362 -0.0981755 -0.10121676 -0.10437601 -0.10751541 -0.11068545 -0.11396523 -0.11715034 -0.12042454 -0.12376312 -0.12702382 -0.1303688 -0.13374267 -0.13705361 -0.14043952 -0.14384645 -0.14719472 -0.15061701 -0.15407716 -0.15747246 -0.16094386 -0.1644846 -0.16793784 -0.1714649 -0.17506487 -0.17860157 -0.18216573 -0.18578893 -0.18939841 -0.19297407 -0.1966009 -0.2002752 -0.20385363 -0.20748051 -0.21115806 -0.21481043 -0.21844447 -0.22212957 -0.22586827 -0.22952503 -0.23322878 -0.23698715 -0.24075826 -0.2444901 -0.24827307 -0.25210748 -0.25591535 -0.25971844 -0.26356709 -0.26746119 -0.27130046 -0.27515629 -0.27905147 -0.28298579 -0.28684611 -0.29073464 -0.29465827 -0.29861516 -0.30249672 -0.30641233 -0.31036412 -0.31434897 -0.31826506 -0.32221836 -0.32621119 -0.3302442 -0.33420809 -0.3382106 -0.34225298 -0.34633637 -0.35036028 -0.35441217 -0.35850248 -0.36263212 -0.36672218 -0.37082111 -0.37495654 -0.37912941 -0.38328856 -0.38743211 -0.39161008 -0.39582301 -0.40005114 -0.40423353 -0.40844727 -0.41269335 -0.41697296 -0.42120348 -0.42544951 -0.42972681 -0.43403657 -0.43833714 -0.44261364 -0.44692107 -0.45126129 -0.45563597 -0.45994653 -0.46428732 -0.46866181 -0.47307211 -0.47747123 -0.48185249 -0.48626774 -0.49071804 -0.49520442 -0.49963345 -0.50408588 -0.50856997 -0.51308593 -0.51760547 -0.5220828 -0.52658674 -0.53111728 ! WE_FOPoles - First order system poles + +!------- YAW CONTROL ------------------------------------------------------ +0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) +0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.0 ! Y_MErrSet - Yaw alignment error, set point [rad] +0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0 ! Y_Rate - Yaw rate [rad/s] + +!------- TOWER FORE-AFT DAMPING ------------------------------------------- +-1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag +0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] + +!------- PEAK SHAVING ------------------------------------------- +210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01745329 -0.01481359 -0.00852004 -0.00261207 0.00300263 0.00835639 0.01335417 0.01816144 0.02266468 0.02700407 0.03107901 0.03503503 0.03873668 0.04233691 0.04576122 0.0490487 0.05224851 0.05526934 0.04650657 0.04921601 0.05191682 0.05454926 0.05716279 0.05977029 0.06234054 0.06487328 0.06740249 0.0699266 0.07239142 0.07485469 0.0773173 0.07975141 0.08215689 0.08456229 0.08696831 0.08932766 0.09168042 0.09403387 0.09638001 0.09868437 0.10098989 0.10329739 0.10558875 0.107852 0.11011795 0.11238745 0.11463538 0.11686407 0.11909634 0.12133285 0.12354431 0.12574081 0.12793997 0.13014217 0.13231708 0.1344781 0.13664176 0.13880903 0.14095272 0.14308312 0.14521797 0.14735847 0.14948186 0.15159016 0.15370444 0.15582544 0.15793469 0.16002168 0.16211269 0.16420811 0.16629762 0.16835609 0.17041755 0.17248274 0.17455211 0.17658169 0.17861473 0.1806522 0.1826952 0.18471218 0.18672192 0.18873761 0.1907605 0.19277392 0.19476714 0.19676698 0.19877416 0.20078773 0.20276435 0.20474671 0.20673544 0.20873123 0.2107031 0.21266276 0.21462751 0.21659806 0.21856498 0.22049786 0.22243509 0.22437749 0.22632594 0.2282473 0.23015988 0.23207809 0.23400295 0.23592811 0.23782196 0.23972214 0.24162947 0.24354474 0.24544163 0.2473258 0.24921658 0.25111458 0.2530204 0.25488953 0.25676337 0.2586437 0.26053106 0.26241124 0.26426775 0.2661302 0.26799913 0.2698751 0.2717283 0.27357125 0.27542013 0.27727554 0.2791381 0.28096271 0.28278987 0.28462312 0.2864631 0.28830169 0.29010619 0.29191673 0.29373402 0.29555876 0.29737371 0.29916551 0.30096387 0.30276933 0.30458242 0.30637934 0.30816157 0.30995024 0.31174576 0.31354853 0.31532916 0.31710053 0.31887775 0.32066115 0.32245108 0.32421484 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/Tune_Cases/DISCON_NREL15MW.IN b/Tune_Cases/DISCON_NREL15MW.IN new file mode 100644 index 000000000..e06c1c9bb --- /dev/null +++ b/Tune_Cases/DISCON_NREL15MW.IN @@ -0,0 +1,103 @@ +! Controller parameter input file for the NREL15mw_OpenFAST_prelim_v4 wind turbine +! - File written using NREL Baseline Controller tuning logic on 10/01/19 + +!------- DEBUG ------------------------------------------------------------ +1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file + +!------- CONTROLLER FLAGS ------------------------------------------------- +1 ! F_LPFType - {1: first-order low-pass filter, 2: second-order low-pass filter}, [rad/s] (currently filters generator speed and pitch control signals) +0 ! F_NotchType - Notch on the measured generator speed {0: disable, 1: enable} +0 ! IPC_ControlMode - Turn Individual Pitch Control (IPC) for fatigue load reductions (pitch contribution) {0: off, 1: 1P reductions, 2: 1P+2P reductions} +2 ! VS_ControlMode - Generator torque control mode in above rated conditions {0: constant torque, 1: constant power, 2: TSR tracking PI control} +1 ! PC_ControlMode - Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} +0 ! Y_ControlMode - Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} +1 ! SS_Mode - Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} +2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Imersion and Invariance Estimator (Ortega et al.)} +1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} + +!------- FILTERS ---------------------------------------------------------- +1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] +0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] +0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] +0.5 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [Hz]. + +!------- BLADE PITCH CONTROL ---------------------------------------------- +136 ! PC_GS_n - Amount of gain-scheduling table entries +0. 0.020256 0.03332726 0.04384533 0.05285897 0.06098095 0.0683739 0.07527681 0.08180782 0.08804439 0.09393203 0.09959529 0.10510496 0.11035197 0.11548427 0.12046262 0.12529554 0.13003978 0.13462978 0.13916723 0.14355684 0.14791037 0.15213125 0.15631919 0.16039651 0.1644349 0.1683878 0.17228887 0.17613395 0.17990923 0.18366134 0.18732062 0.19096834 0.19454319 0.19808351 0.20159304 0.20503245 0.20846304 0.21183023 0.21516765 0.21849054 0.22174071 0.22498441 0.22819373 0.23135658 0.23451421 0.23762464 0.2407075 0.24378595 0.2468094 0.24981721 0.25282098 0.25576684 0.25870376 0.26163702 0.26451402 0.26738435 0.2702515 0.27306798 0.27587635 0.27868204 0.28144576 0.28419677 0.28694553 0.28966309 0.29236066 0.29505604 0.29773223 0.30037881 0.303023 0.3056614 0.30825919 0.31085446 0.3134475 0.31600991 0.31855897 0.32110571 0.32363936 0.32614484 0.32864796 0.33114905 0.33361989 0.33608194 0.33854196 0.34099154 0.34341533 0.3458371 0.34825716 0.35065537 0.35304125 0.35542509 0.35780697 0.36015841 0.36250745 0.36485432 0.3671914 0.36950687 0.3718198 0.37413044 0.37642575 0.37870606 0.38098377 0.38325913 0.38551585 0.38776234 0.39000628 0.39224794 0.39446964 0.39668423 0.39889642 0.40110649 0.40329679 0.40548162 0.40766422 0.40984486 0.41200694 0.41416387 0.41631855 0.41847115 0.42060682 0.42273639 0.42486345 0.42698821 0.42760567 0.42760567 0.42760567 0.42760567 0.42760567 0.42760567 0.42760567 0.42760567 0.42760567 0.42760567 0.42760567 0.42760567 0.42760567 ! PC_GS_angles - Gain-schedule table: pitch angles +-4.46003791 -4.32216423 -4.19157647 -4.06771197 -3.95006453 -3.83817755 -3.73163805 -3.63007161 -3.53313798 -3.44052725 -3.35195655 -3.26716715 -3.18592198 -3.10800334 -3.03321105 -2.96136063 -2.89228187 -2.82581742 -2.76182163 -2.70015946 -2.64070557 -2.58334341 -2.52796449 -2.47446773 -2.42275876 -2.37274944 -2.32435732 -2.27750521 -2.23212075 -2.18813604 -2.1454873 -2.10411458 -2.06396146 -2.02497479 -1.98710447 -1.95030323 -1.91452643 -1.87973187 -1.84587967 -1.81293204 -1.78085321 -1.74960926 -1.71916801 -1.68949893 -1.66057299 -1.63236264 -1.60484163 -1.57798501 -1.551769 -1.52617095 -1.50116927 -1.47674335 -1.45287354 -1.42954106 -1.40672796 -1.3844171 -1.36259206 -1.34123715 -1.32033735 -1.29987826 -1.27984607 -1.26022758 -1.24101009 -1.22218144 -1.20372994 -1.18564437 -1.16791395 -1.15052832 -1.13347753 -1.116752 -1.10034249 -1.08424015 -1.06843642 -1.05292307 -1.03769218 -1.0227361 -1.00804746 -0.99361915 -0.97944431 -0.96551632 -0.95182878 -0.93837553 -0.92515059 -0.91214821 -0.89936281 -0.88678901 -0.8744216 -0.86225553 -0.85028593 -0.83850809 -0.82691742 -0.8155095 -0.80428004 -0.79322489 -0.78234002 -0.77162153 -0.76106563 -0.75066864 -0.74042702 -0.73033729 -0.72039611 -0.71060022 -0.70094645 -0.69143175 -0.68205311 -0.67280765 -0.66369255 -0.65470508 -0.64584256 -0.63710241 -0.62848211 -0.61997922 -0.61159136 -0.60331619 -0.59515148 -0.58709502 -0.57914467 -0.57129835 -0.56355404 -0.55590975 -0.54836356 -0.54091359 -0.53355802 -0.52629506 -0.51912298 -0.51204007 -0.50504469 -0.49813523 -0.4913101 -0.48456778 -0.47790677 -0.47132561 -0.46482286 -0.45839714 -0.45204708 -0.44577136 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-1.89116623 -1.83984083 -1.79122773 -1.74511744 -1.70132155 -1.65967006 -1.62000925 -1.58219973 -1.54611484 -1.51163921 -1.47866753 -1.4471035 -1.41685886 -1.38785256 -1.36001009 -1.33326277 -1.30754724 -1.28280493 -1.2589816 -1.23602701 -1.21389447 -1.19254061 -1.17192504 -1.15201012 -1.13276074 -1.11414407 -1.09612943 -1.07868809 -1.06179309 -1.04541917 -1.02954258 -1.01414101 -0.99919345 -0.98468012 -0.97058237 -0.9568826 -0.94356419 -0.93061143 -0.91800948 -0.90574426 -0.89380247 -0.88217148 -0.8708393 -0.85979457 -0.84902649 -0.83852479 -0.82827971 -0.81828196 -0.80852269 -0.79899346 -0.78968624 -0.78059335 -0.77170748 -0.76302164 -0.75452915 -0.74622362 -0.73809894 -0.73014928 -0.72236904 -0.71475286 -0.7072956 -0.69999234 -0.69283837 -0.68582914 -0.67896031 -0.6722277 -0.66562731 -0.65915527 -0.65280788 -0.64658156 -0.6404729 -0.63447857 -0.62859542 -0.62282036 -0.61715045 -0.61158284 -0.60611479 -0.60074365 -0.59546687 -0.59028198 -0.5851866 -0.58017844 -0.57525528 -0.57041496 -0.56565542 -0.56097464 -0.5563707 -0.55184171 -0.54738587 -0.5430014 -0.53868661 -0.53443985 -0.53025953 -0.5261441 -0.52209206 -0.51810195 -0.51417237 -0.51030194 -0.50648936 -0.50273332 -0.49903257 -0.49538592 -0.49179217 -0.48825019 -0.48475886 -0.48131711 -0.47792389 -0.47457817 -0.47127898 -0.46802533 -0.46481631 -0.46165099 -0.45852849 -0.45544795 -0.45240852 -0.44940939 -0.44644976 -0.44352886 -0.44064593 -0.43780024 -0.43499106 -0.43221771 -0.4294795 -0.42677576 -0.42410585 -0.42146914 -0.41886501 -0.41629287 -0.41375212 -0.4112422 -0.40876254 -0.40631261 -0.40389188 -0.40149981 -0.39913592 -0.39679969 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. +-0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. +122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] +0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] +0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] +0.0349066 ! Z_PitchAmplitude - Amplitude of sine pitch excitation, [rad] +0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] + +!------- INDIVIDUAL PITCH CONTROL ----------------------------------------- +0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] + +!------- VS TORQUE CONTROL ------------------------------------------------ +0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. +91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5.0E+06 ! VS_RtPwr - Wind turbine rated power [W] +43093.55 ! VS_RtTq - Rated torque, [Nm]. +120.113 ! VS_RefSpd - Rated generator speed [rad/s] +1 ! VS_n - Number of generator PI torque controller gains +-835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) + +!------- SETPOINT SMOOTHER --------------------------------------------- +30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. +0.001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. + +!------- WIND SPEED ESTIMATOR --------------------------------------------- +63.0 ! WE_BladeRadius - Blade length [m] +4 ! WE_CP_n - Amount of parameters in the Cp array +14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function +20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +1.225 ! WE_RhoAir - Air density, [kg m^-3] +"../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) +320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +23 ! WE_FOPoles_N - Number of first-order system poles used in EKF +3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles + +!------- YAW CONTROL ------------------------------------------------------ +1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) +-0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +-0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad] +1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0034906 ! Y_Rate - Yaw rate [rad/s] + +!------- TOWER FORE-AFT DAMPING ------------------------------------------- +-1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag +0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] + +!------- PEAK SHAVING ------------------------------------------- +210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0.00210969 0.00829863 0.01412672 0.01969173 0.02498447 0.02996603 0.03475996 0.03922425 0.04355892 0.0476194 0.05156694 0.05530958 0.05892744 0.06241098 0. 0. 0. 0. 0. 0. 0.00083802 0.00375952 0.00669792 0.00960784 0.01242754 0.01526655 0.01809319 0.02082473 0.02357686 0.02634414 0.02899762 0.03167203 0.03437059 0.03698078 0.03958414 0.04221122 0.04480093 0.04733897 0.0499 0.05248032 0.05495785 0.05745744 0.05998167 0.06245845 0.06490078 0.06736653 0.06985598 0.07224489 0.07465609 0.07709188 0.07950281 0.08186268 0.08424543 0.08665316 0.08899472 0.09132689 0.09368224 0.09605936 0.09834389 0.10065008 0.10297987 0.10530466 0.10756529 0.10984822 0.11215534 0.1144365 0.11667541 0.11893661 0.12122177 0.12346473 0.12568171 0.12792057 0.13018287 0.13239229 0.13458701 0.13680324 0.13904252 0.14122376 0.14339678 0.14559122 0.14780877 0.14996817 0.15212176 0.15429696 0.15649522 0.1586386 0.16077418 0.16293093 0.16511013 0.1672407 0.16935778 0.17149525 0.1736543 0.17577418 0.17787164 0.17998863 0.18212628 0.18423762 0.18631464 0.18841046 0.19052617 0.19263176 0.19468874 0.19676436 0.19885985 0.20096441 0.20300387 0.20506181 0.20713929 0.20923738 0.2112696 0.21331071 0.21537071 0.21745054 0.21948885 0.22151272 0.22355459 0.22561531 0.22766021 0.22966583 0.23168844 0.23372885 0.23578053 0.23776673 0.23976895 0.24178795 0.2438245 0.24581279 0.247794 0.24979116 0.25180516 0.25380442 0.25576558 0.2577425 0.259736 0.26174694 0.26369244 0.26565116 0.26762603 0.26961781 0.27158165 0.27352338 0.27548063 0.27745407 0.2794366 0.28136146 0.28330104 0.28525593 0.28722677 0.28916414 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/Tune_Cases/NREL15MW_turbine.p b/Tune_Cases/NREL15MW_turbine.p new file mode 100644 index 000000000..78e22dc54 Binary files /dev/null and b/Tune_Cases/NREL15MW_turbine.p differ diff --git a/Tune_Cases/tune_NREL15MW.py b/Tune_Cases/tune_NREL15MW.py new file mode 100644 index 000000000..7bff72328 --- /dev/null +++ b/Tune_Cases/tune_NREL15MW.py @@ -0,0 +1,92 @@ +# NREL 15MW Baseline +# Example_07 +# Load gain schedules, write_paramter input file, plot gains + +#%% +import numpy as np +from scipy import interpolate +import matplotlib.pyplot as plt + +from WTC_toolbox import controller as wtc_controller +from WTC_toolbox import turbine as wtc_turbine +from WTC_toolbox import sim as wtc_sim + +import os + +os.chdir('/Users/nabbas/Documents/WindEnergyToolbox/WTC_toolbox/Tune_Cases') + +# Initialiize turbine and controller classes +turbine = wtc_turbine.Turbine() +controller = wtc_controller.Controller() +file_processing = wtc_controller.FileProcessing() + +# Fast input file and Cp surface text file +# FAST_InputFile = 'NREL15mw_OpenFAST_prelim_v4.fst' +# FAST_directory = '/Users/nabbas/Documents/TurbineModels/NREL-15MW-Offshore-Reference-Turbine/OpenFAST/NREL15mw_OpenFAST_prelim_v4' +# txt_filename = 'Cp_Ct_Cq.txt' + +FAST_InputFile = '5MW_Land.fst' +FAST_directory = '/Users/nabbas/Documents/TurbineModels/NREL_5MW/5MW_Land' +txt_filename = 'Cp_Ct_Cq.txt' + +# rotor_inertia = 354810226.448 # Available from Elastodyn I/O +# generator_inertia = 17159301.77 +# gb_ratio = 97 +# drivetrain_inertia = rotor_inertia + generator_inertia* gb_ratio**2 + +drivetrain_inertia = 40469564.444 + +# turbine.load('NREL15MW_turbine.p') + +# Load Turbine +# turbine.load_from_fast(FAST_InputFile,FAST_directory,drivetrain_inertia,dev_branch=True,rot_source='txt',txt_filename=txt_filename) +turbine.load_from_fast(FAST_InputFile,FAST_directory,drivetrain_inertia,dev_branch=True,rot_source=None,txt_filename=txt_filename) +# Tune controller +controller.tune_controller(turbine) +# Save turbine +turbine.save('NREL15MW_turbine.p') + + +#%% +turbine.write_rotorperformance(txt_filename='Cp_Ct_Cq.txt') + +# Write parameter input file +param_file = 'DISCON.IN' +file_processing.write_param_file(param_file,turbine,controller,new_file=True) + + +#%% Load Saved Turbine +# turbine.load('NREL15MW_turbine.p') + +#%% Tiny sim +from WTC_toolbox import control_interface as ci + +# Load controller +lib_name = '../DRC_Fortran/DISCON/DISCON_glin64.so' +# lib_name = '/Users/pfleming/Desktop/git_tools/floating/DRC_Fortran/DISCON//DISCON_glin64.so' +controller_int = ci.ConInt(lib_name) + +# Load the simulator +sim = wtc_sim.Sim(turbine,controller_int) + +# Define a wind speed history +dt = 0.1 +tlen = 500 # length of time to simulate (s) +ws0 = 9 # initial wind speed (m/s) +t= np.arange(0,tlen,dt) +ws = np.ones_like(t) * ws0 +# add steps at every 100s +# for i in range(len(t)): +# ws[i] = ws[i] + t[i]//100 + + +# Run simulator +sim.sim_ws_series(t,ws) +plt.show() + +#%% +plt.figure(1) +plt.plot(controller.pc_gain_schedule.Kp) +plt.show() + +print(controller.v_rated) \ No newline at end of file diff --git a/WTC_toolbox/control_interface.py b/WTC_toolbox/control_interface.py index a729a0a3b..ef3b5bf58 100644 --- a/WTC_toolbox/control_interface.py +++ b/WTC_toolbox/control_interface.py @@ -91,7 +91,7 @@ def call_discon(self): self.avrSWAP = data - def call_controller(self,t,dt,pitch,genspeed,rotspeed,ws): + def call_controller(self,t,dt,pitch,torque,genspeed,rotspeed,ws): ''' Runs the controller. Passes current turbine state to the controller, and returns control inputs back @@ -115,6 +115,7 @@ def call_controller(self,t,dt,pitch,genspeed,rotspeed,ws): self.avrSWAP[1] = t self.avrSWAP[2] = dt self.avrSWAP[3] = self.pitch + self.avrSWAP[22] = torque self.avrSWAP[19] = genspeed self.avrSWAP[20] = rotspeed self.avrSWAP[26] = ws diff --git a/WTC_toolbox/controller.py b/WTC_toolbox/controller.py index b8fedd3e2..22e726d22 100644 --- a/WTC_toolbox/controller.py +++ b/WTC_toolbox/controller.py @@ -31,7 +31,7 @@ class Controller(): def __init__(self): pass - def controller_params(self): + def controller_params(self,turbine): # Hard coded controller parameters for turbine. Using this until read_param_file is good to go # - Coded for NREL 5MW @@ -41,11 +41,13 @@ def controller_params(self): # Torque Controller Parameters self.zeta_vs = 0.7 # Torque controller damping ratio (-) - self.omega_vs = 0.3 # Torque controller natural frequency (rad/s) + self.omega_vs = 0.2 # Torque controller natural frequency (rad/s) # Other basic parameters - self.v_rated = 11.4 # Rated wind speed (m/s) - + # self.v_rated = turbine.RRspeed * turbine.RotorRad / turbine.TSR_initial[turbine.Cp.max_ind[0]] # Rated wind speed (m/s) + # self.v_rated = 10.75 + self.v_rated = 11.4 + def tune_controller(self, turbine): """ Given a turbine model, tune the controller parameters @@ -61,7 +63,7 @@ def tune_controller(self, turbine): # Load controller parameters # - should be self.read_param_file() eventually, hard coded for now - self.controller_params() + self.controller_params(turbine) # Re-define controller tuning parameters for shorthand zeta_pc = self.zeta_pc # Pitch controller damping ratio @@ -76,8 +78,8 @@ def tune_controller(self, turbine): TSR_rated = RRspeed*R/v_rated # TSR at rated # separate wind speeds by operation regions - v_below_rated = np.arange(v_min,v_rated,0.1) # below rated - v_above_rated = np.arange(v_rated,v_max,0.1) # above rated + v_below_rated = np.arange(v_min,v_rated,0.5) # below rated + v_above_rated = np.arange(v_rated+0.5,v_max,0.5) # above rated v = np.concatenate((v_below_rated, v_above_rated)) # separate TSRs by operations regions @@ -126,7 +128,7 @@ def tune_controller(self, turbine): # Wind Disturbance Input dlambda_dv = -(TSR_op/v) dtau_dv = dtau_dlambda*dlambda_dv - B_v = dtau_dv/J # wind speed input - currently unused + # B_v = dtau_dv/J # wind speed input - currently unused # separate and define below and above rated parameters @@ -151,6 +153,7 @@ def tune_controller(self, turbine): self.TSR_op = TSR_op self.A = A self.B_beta = B_beta + self.B_tau = B_tau # Peak Shaving self.ps = ControllerBlocks() @@ -259,9 +262,9 @@ def read_param_file(self, param_file): # Setpoint Smoother Parameters self.Kss_PC = param_file.Kss_PC # Pitch controller reference gain bias self.Kss_VS = param_file.Kss_VS # Torque controller reference gain bias - self.v_min = turbine.VS_Vmin # Cut-in wind speed (m/s) - self.v_rated = turbine.PC_Vrated # Rated wind speed (m/s) - self.v_max = turbine.PC_Vmax # Cut-out wind speed (m/s), -- Does not need to be exact + self.v_min = turbine.v_min # Cut-in wind speed (m/s) + self.v_rated = turbine.v_rated # Rated wind speed (m/s) + self.v_max = turbine.v_max # Cut-out wind speed (m/s), -- Does not need to be exact def write_param_file(self, param_file, turbine, controller, new_file=True): @@ -294,11 +297,11 @@ class containing file.write('1 ! PC_ControlMode - Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control}\n') file.write('0 ! Y_ControlMode - Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC}\n') file.write('1 ! SS_Mode - Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing}\n') - file.write('2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Imersion and Invariance Estimator (Ortega et al.)}\n') + file.write('0 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Imersion and Invariance Estimator (Ortega et al.)}\n') file.write('1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving}\n') file.write('\n') file.write('!------- FILTERS ----------------------------------------------------------\n') - file.write('1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz]\n') # this needs to be included as an input file + file.write('{} ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz]\n'.format(str(turbine.omega_dt * 1/3))) # this needs to be included as an input file file.write('0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2]\n') file.write('0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s]\n') file.write('0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-]\n') @@ -311,11 +314,11 @@ class containing file.write('{} ! PC_GS_KI - Gain-schedule table: pitch controller ki gains\n'.format(str(controller.pc_gain_schedule.Ki).strip('[]').replace('\n',''))) file.write('{} ! PC_GS_KD - Gain-schedule table: pitch controller kd gains\n'.format(str(np.zeros(len(controller.pitch_op_pc))).strip('[]').replace('\n',''))) file.write('{} ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter)\n'.format(str(np.zeros(len(controller.pitch_op_pc))).strip('[]').replace('\n',''))) - file.write('1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad].\n') - file.write('-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad].\n') + file.write('{} ! PC_MaxPit - Maximum physical pitch limit, [rad].\n'.format(str(turbine.PC_MaxPit))) + file.write('{} ! PC_MinPit - Minimum physical pitch limit, [rad].\n'.format(str(turbine.PC_MinPit))) file.write('0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s].\n') file.write('-0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s].\n') - file.write('122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s].\n') + file.write('{} ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s].\n'.format(str(turbine.RRspeed*turbine.Ng))) file.write('0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad]\n') file.write('0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad]\n') file.write('0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-]\n') @@ -323,61 +326,62 @@ class containing file.write('0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s]\n') file.write('\n') file.write('!------- INDIVIDUAL PITCH CONTROL -----------------------------------------\n') - file.write('0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad]\n') - file.write('1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-]\n') - file.write('0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. \n') - file.write('2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s]\n') + file.write('0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad]\n') + file.write('0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-]\n') + file.write('0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. \n') + file.write('0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s]\n') file.write('\n') file.write('!------- VS TORQUE CONTROL ------------------------------------------------\n') - file.write('0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-]\n') - file.write('43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm]\n') - file.write('150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s].\n') - file.write('48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm].\n') + file.write('{} ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-]\n'.format(turbine.GenEff)) + file.write('{} ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm]\n'.format(turbine.RatedTorque)) + file.write('1500000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s].\n') + file.write('{} ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm].\n'.format(str(turbine.RatedTorque*1.1))) file.write('0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm].\n') - file.write('91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s]\n') - file.write('2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2]\n') - file.write('5.0E+06 ! VS_RtPwr - Wind turbine rated power [W]\n') - file.write('43093.55 ! VS_RtTq - Rated torque, [Nm].\n') - file.write('120.113 ! VS_RefSpd - Rated generator speed [rad/s]\n') + file.write('0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s]\n') + file.write('0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2]\n') + file.write('{} ! VS_RtPwr - Wind turbine rated power [W]\n'.format(str(turbine.RatedPower))) + file.write('{} ! VS_RtTq - Rated torque, [Nm].\n'.format(str(turbine.RatedTorque))) + file.write('{} ! VS_RefSpd - Rated generator speed [rad/s]\n'.format(str(turbine.RRspeed*turbine.Ng))) file.write('1 ! VS_n - Number of generator PI torque controller gains\n') - file.write('-835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2)\n') - file.write('-164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2)\n') + file.write('{} ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2)\n'.format(str(controller.vs_gain_schedule.Kp[-1]))) + file.write('{} ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2)\n'.format(str(controller.vs_gain_schedule.Ki[-1]))) + file.write('{} ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad].\n'.format(str(turbine.Cp.TSR_opt).strip('[]'))) file.write('\n') file.write('!------- SETPOINT SMOOTHER ---------------------------------------------\n') file.write('30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad].\n') file.write('0.001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm].\n') file.write('\n') file.write('!------- WIND SPEED ESTIMATOR ---------------------------------------------\n') - file.write('63.0 ! WE_BladeRadius - Blade length [m]\n') + file.write('{} ! WE_BladeRadius - Blade length [m]\n'.format(str(turbine.RotorRad))) file.write('4 ! WE_CP_n - Amount of parameters in the Cp array\n') - file.write('14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function\n') - file.write('20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad]\n') - file.write('97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-]\n') - file.write('4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2]\n') + file.write('0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function\n') + file.write('0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad]\n') + file.write('{} ! WE_GearboxRatio - Gearbox ratio [>=1], [-]\n'.format(str(turbine.Ng))) + file.write('{} ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2]\n'.format(str(turbine.J))) file.write('1.225 ! WE_RhoAir - Air density, [kg m^-3]\n') - file.write('"../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq)\n') - file.write('320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios\n') - file.write('23 ! WE_FOPoles_N - Number of first-order system poles used in EKF\n') - file.write('3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s]\n') - file.write('-0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles\n') + file.write('"Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq)\n') + file.write('{} {} ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios\n'.format(str(len(turbine.Cp.pitch_initial_rad)),str(len(turbine.Cp.TSR_initial)))) + file.write('{} ! WE_FOPoles_N - Number of first-order system poles used in EKF\n'.format(str(len(controller.A)))) + file.write('{} ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s]\n'.format(str(controller.v).strip('[]').replace('\n',''))) + file.write('{} ! WE_FOPoles - First order system poles\n'.format(str(controller.A).strip('[]').replace('\n',''))) file.write('\n') file.write('!------- YAW CONTROL ------------------------------------------------------\n') - file.write('1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s]\n') - file.write('0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad]\n') + file.write('0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s]\n') + file.write('0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad]\n') file.write('1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC)\n') - file.write('-0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp\n') - file.write('-0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki\n') - file.write('0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s].\n') - file.write('1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-].\n') - file.write('0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad]\n') - file.write('1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz]\n') - file.write('0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz]\n') - file.write('0.0034906 ! Y_Rate - Yaw rate [rad/s]\n') + file.write('0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp\n') + file.write('0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki\n') + file.write('0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s].\n') + file.write('0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-].\n') + file.write('0.0 ! Y_MErrSet - Yaw alignment error, set point [rad]\n') + file.write('0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz]\n') + file.write('0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz]\n') + file.write('0.0 ! Y_Rate - Yaw rate [rad/s]\n') file.write('\n') file.write('!------- TOWER FORE-AFT DAMPING -------------------------------------------\n') file.write('-1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag\n') - file.write('0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s]\n') - file.write('0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad]\n') + file.write('0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s]\n') + file.write('0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad]\n') file.write('\n') file.write('!------- PEAK SHAVING -------------------------------------------\n') file.write('{} ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin)\n'.format(len(controller.ps.pitch_min))) diff --git a/WTC_toolbox/sim.py b/WTC_toolbox/sim.py index bc5cc12a4..4cce3a52b 100644 --- a/WTC_toolbox/sim.py +++ b/WTC_toolbox/sim.py @@ -105,7 +105,7 @@ def sim_ws_series(self,t_array,ws_array,rotor_rpm_init=10,init_pitch=0.0, make_p gen_speed[i] = rot_speed[i] * self.turbine.Ng # Call the controller - gen_torque[i], bld_pitch[i] = self.controller_int.call_controller(t,dt,bld_pitch[i-1],gen_speed[i],rot_speed[i],ws) + gen_torque[i], bld_pitch[i] = self.controller_int.call_controller(t,dt,bld_pitch[i-1],gen_torque[i-1],gen_speed[i],rot_speed[i],ws) # Calculate the power gen_power[i] = gen_speed[i] * np.pi/30.0 * gen_torque[i] * self.gen_eff diff --git a/WTC_toolbox/turbine.py b/WTC_toolbox/turbine.py index b554ede75..6a56d34e2 100644 --- a/WTC_toolbox/turbine.py +++ b/WTC_toolbox/turbine.py @@ -20,6 +20,7 @@ deg2rad = np.deg2rad(1) rad2deg = np.rad2deg(1) rpm2RadSec = 2.0*(np.pi)/60.0 +RadSec2rpm = 60/(2.0 * np.pi) class Turbine(): """ @@ -33,22 +34,23 @@ def __init__(self): This also lists what will need to be defined """ + # ------ Turbine Parameters------ + self.RRspeed = 12.1*rpm2RadSec # Rated rotor speed (rad/s) + # self.RRspeed = 7.5*rpm2RadSec # Rated rotor speed (rad/s) - # Turbine Parameters - self.J = None # Total rotor inertial (kg-m^2) - self.rho = None # Air density (kg/m^3) - self.RotorRad = None # Rotor radius (m) - self.Ng = None # Gearbox ratio (-) - self.RRspeed = None # Rated rotor speed (rad/s) self.v_min = 4. # Cut-in wind speed (m/s) (JUST ASSUME FOR NOW) self.v_rated = None # Rated wind speed (m/s) self.v_max = 25. # Cut-out wind speed (m/s), -- Does not need to be exact (JUST ASSUME FOR NOW) + self.RatedPower = 5000000 + # self.RatedPower = 15000000 + # Pitch controller + self.PC_MaxPit = 1.5707 # Maximum pitch angle (rad) + self.PC_MinPit = -0.087266 # Minimum pitch angle (rad) # Init the cc-blade rotor self.cc_rotor = None - # Pitch controller - self.PC_MinPit = -0.087266 # Minimum pitch angle (rad) + # Interp function versions self.cp_interp = None @@ -68,7 +70,7 @@ def __str__(self): # Save function def save(self,filename): - tuple_to_save = (self.J,self.rho,self.RotorRad, self.Ng,self.RRspeed,self.v_min,self.v_rated,self.v_max,self.cc_rotor,self.Cp,self.Ct,self.Cq ) + tuple_to_save = (self.J,self.rho,self.RotorRad, self.Ng,self.RRspeed,self.v_min,self.v_rated,self.v_max,self.cc_rotor,self.Cp_table,self.Ct_table,self.Cq_table,self.Cp,self.Ct,self.Cq ) pickle.dump( tuple_to_save, open( filename, "wb" ) ) # Load function @@ -115,16 +117,24 @@ def load_from_fast(self, FAST_InputFile,FAST_directory,drivetrain_inertia, FAST_ self.TipRad = fast.fst_vt['ElastoDyn']['TipRad'] self.Rhub = fast.fst_vt['ElastoDyn']['HubRad'] self.hubHt = fast.fst_vt['ElastoDyn']['TowerHt'] - self.shearExp = 0.2 #HARD CODED UNTIL FIND A SOLUTION TO READ OUTPUT + self.shearExp = 0.2 #HARD CODED FOR NOW self.rho = fast.fst_vt['AeroDyn15']['AirDens'] self.mu = fast.fst_vt['AeroDyn15']['KinVisc'] self.Ng = fast.fst_vt['ElastoDyn']['GBRatio'] - + self.GenEff = fast.fst_vt['ServoDyn']['GenEff'] + self.DTTorSpr = fast.fst_vt['ElastoDyn']['DTTorSpr'] + self.RatedTorque = self.RatedPower/(self.GenEff/100*self.RRspeed*self.Ng) + + # Some additional parameters to save self.RotorRad = self.TipRad + self.omega_dt = np.sqrt(self.DTTorSpr/self.J) + if self.RRspeed: + pass + else: + # Calculate rated rotor speed by scaling from NREL 5MW + self.RRspeed = (63. / self.TipRad) * 12.1 * rpm2RadSec - # Calculate rated rotor speed for now by scaling from NREL 5MW - self.RRspeed = (63. / self.TipRad) * 12.1 * rpm2RadSec # Load Cp, Ct, Cq tables if rot_source == 'txt': @@ -149,19 +159,6 @@ def load_from_ccblade(self,fast): af_idx = np.array(fast.fst_vt['AeroDynBlade']['BlAFID']).astype(int) - 1 #Reset to 0 index AFNames = fast.fst_vt['AeroDyn15']['AFNames'] - # # NEED A PRETTY SERIOUS HACK TO POINT AT OLD AIRFOIL TABLES - # ad14path = '/Users/pfleming/Desktop/git_tools/FLORIS/examples/5MW_AFFiles' - # AFNames_14 = [] - # for airfoil in AFNames: - # a_name = os.path.basename(airfoil) - # AFNames_14.append(os.path.join(ad14path,a_name)) - # print(fast.FAST_directory) - - # # Load in the airfoils - # afinit = CCAirfoil.initFromAerodynFile # just for shorthand - # airfoil_types = [] - # for airfoil in AFNames: - # airfoil_types.append(afinit(airfoil)) # Used airfoil data from FAST file read, assumes AeroDyn 15, assumes 1 Re num per airfoil af_dict = {} @@ -194,20 +191,20 @@ def load_from_ccblade(self,fast): print('CCBlade run succesfully') # Generate the look-up tables # Mesh the grid and flatten the arrays - fixed_rpm = 10 # RPM + fixed_rpm = self.RRspeed*RadSec2rpm # RPM TSR_initial = np.arange(0.5,15,0.5) - pitch_initial = np.arange(0,25,0.5) + pitch_initial = np.arange(-1,25,0.5) pitch_initial_rad = pitch_initial * deg2rad - ws_array = (fixed_rpm * (np.pi / 30.) * self.TipRad) / TSR_initial + ws_array = (fixed_rpm * rpm2RadSec * self.TipRad) / TSR_initial ws_mesh, pitch_mesh = np.meshgrid(ws_array, pitch_initial) ws_flat = ws_mesh.flatten() pitch_flat = pitch_mesh.flatten() omega_flat = np.ones_like(pitch_flat) * fixed_rpm - tsr_flat = (fixed_rpm * (np.pi / 30.) * self.TipRad) / ws_flat + tsr_flat = (fixed_rpm * rpm2RadSec * self.TipRad) / ws_flat # Get values from cc-blade - print('Running cc_rotor aerodynamic analysis...') + print('Running cc_rotor aerodynamic analysis, this may take a second...') P, T, Q, M, CP, CT, CQ, CM = self.cc_rotor.evaluate(ws_flat, omega_flat, pitch_flat, coefficients=True) # Reshape Cp, Ct and Cq @@ -267,7 +264,52 @@ def load_from_txt(self,fast,txt_filename): self.Cp_table = Cp self.Ct_table = Ct self.Cq_table = Cq + + + def write_rotorperformance(self,txt_filename='Cp_Ct_Cq.txt'): + ''' + Write text file containing rotor performance data + Parameters: + ------------ + Fill this out... + ''' + + file = open(txt_filename,'w') + file.write('# Pitch angle vector - x axis (matrix columns) (deg)\n') + for i in range(len(self.Cp.pitch_initial_rad)): + file.write('%.2f ' % (self.Cp.pitch_initial_rad[i] * rad2deg)) + file.write('\n# TSR vector - y axis (matrix rows) (-)\n') + for i in range(len(self.TSR_initial)): + file.write('%.2f ' % self.Cp.TSR_initial[i]) + file.write('\n# Wind speed vector - z axis (m/s)\n') + # for i in range(n_U): + # --- write arbitrary wind speed for now... + file.write('%.2f ' % 3.0) + file.write('\n') + + file.write('\n# Power coefficient\n\n') + for i in range(len(self.Cp.TSR_initial)): + for j in range(len(self.Cp.pitch_initial_rad)): + file.write('%.5f ' % self.Cp_table[i,j]) + file.write('\n') + file.write('\n') + + file.write('\n# Thrust coefficient\n\n') + for i in range(len(self.Ct.TSR_initial)): + for j in range(len(self.Ct.pitch_initial_rad)): + file.write('%.5f ' % self.Ct_table[i,j]) + file.write('\n') + file.write('\n') + + file.write('\n# Torque coefficient\n\n') + for i in range(len(self.Cq.TSR_initial)): + for j in range(len(self.Cq.pitch_initial_rad)): + file.write('%.5f ' % self.Cq_table[i,j]) + file.write('\n') + file.write('\n') + + file.close() class RotorPerformance(): def __init__(self,performance_table, pitch_initial_rad, TSR_initial): @@ -304,14 +346,13 @@ def interp_gradient(self,pitch,TSR): return np.ndarray.flatten(grad) +# # NOT CERTAIN OF THESE ALTERNATIVES YET +# def load_from_sowfa(self, fast_folder): +# """ +# Load the parameter files directly from a SOWFA directory +# """ - # # NOT CERTAIN OF THESE ALTERNATIVES YET - # def load_from_sowfa(self, fast_folder): - # """ - # Load the parameter files directly from a SOWFA directory - # """ - - # def load_from_csv(self, fast_folder): - # """ - # Load from a simple CSV file containing the parameters - # """ \ No newline at end of file +# def load_from_csv(self, fast_folder): +# """ +# Load from a simple CSV file containing the parameters +# """ \ No newline at end of file diff --git a/examples/DISCON.IN b/examples/DISCON.IN index 6093abeac..2026db1bb 100644 --- a/examples/DISCON.IN +++ b/examples/DISCON.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the 5MW_Land wind turbine -! - File written using NREL Baseline Controller tuning logic on 09/26/19 +! - File written using NREL Baseline Controller tuning logic on 10/02/19 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file @@ -12,11 +12,11 @@ 1 ! PC_ControlMode - Blade pitch control mode {0: No pitch, fix to fine pitch, 1: active PI blade pitch control} 0 ! Y_ControlMode - Yaw control mode {0: no yaw control, 1: yaw rate control, 2: yaw-by-IPC} 1 ! SS_Mode - Setpoint Smoother mode {0: no setpoint smoothing, 1: introduce setpoint smoothing} -2 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Imersion and Invariance Estimator (Ortega et al.)} +0 ! WE_Mode - Wind speed estimator mode {0: One-second low pass filtered hub height wind speed, 1: Imersion and Invariance Estimator (Ortega et al.)} 1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} !------- FILTERS ---------------------------------------------------------- -1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +4.630253480546613 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] 0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] 0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] 0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] @@ -30,10 +30,10 @@ 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +122.90957658394467 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. 0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] 0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] @@ -41,63 +41,63 @@ 0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] -1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. -2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] +0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] !------- VS TORQUE CONTROL ------------------------------------------------ -0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] -43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +100.0 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +40680.312624664395 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] 150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +44748.34388713084 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. -91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] -2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] -5.0E+06 ! VS_RtPwr - Wind turbine rated power [W] -43093.55 ! VS_RtTq - Rated torque, [Nm]. -120.113 ! VS_RefSpd - Rated generator speed [rad/s] +0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5000000 ! VS_RtPwr - Wind turbine rated power [W] +40680.312624664395 ! VS_RtTq - Rated torque, [Nm]. +122.90957658394467 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-880.4968862680173 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-172.0461874545648 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) !------- SETPOINT SMOOTHER --------------------------------------------- 30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. 0.001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. !------- WIND SPEED ESTIMATOR --------------------------------------------- -63.0 ! WE_BladeRadius - Blade length [m] +63.0 ! WE_BladeRadius - Blade length [m] 4 ! WE_CP_n - Amount of parameters in the Cp array -14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function -20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] -97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +40469564.444 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1.225 ! WE_RhoAir - Air density, [kg m^-3] -"../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) -320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -23 ! WE_FOPoles_N - Number of first-order system poles used in EKF -3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles +"Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) +320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +210 ! WE_FOPoles_N - Number of first-order system poles used in EKF + 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02665071 -0.02731698 -0.02798324 -0.02864951 -0.02931578 -0.02998205 -0.03064832 -0.03131458 -0.03198085 -0.03264712 -0.03331339 -0.03397965 -0.03464592 -0.03531219 -0.03597846 -0.03664473 -0.03731099 -0.03797726 -0.03864353 -0.0393098 -0.03997606 -0.04064233 -0.0413086 -0.04197487 -0.04264113 -0.0433074 -0.04397367 -0.04463994 -0.04530621 -0.04597247 -0.04663874 -0.04730501 -0.04797128 -0.04863754 -0.04930381 -0.04997008 -0.05063635 -0.05130262 -0.05196888 -0.05263515 -0.05330142 -0.05396769 -0.05463395 -0.05530022 -0.05596649 -0.05663276 -0.05729903 -0.05796529 -0.05863156 -0.05929783 -0.0599641 -0.06063036 -0.06129663 -0.0619629 -0.06262917 -0.06329543 -0.0639617 -0.06462797 -0.06529424 -0.06596051 -0.06662677 -0.06729304 -0.06795931 -0.06862558 -0.06929184 -0.06995811 -0.07062438 -0.07129065 -0.07195692 -0.07262318 -0.07328945 -0.07395572 -0.07462199 -0.07528825 -0.06255511 -0.0590773 -0.05859702 -0.059213 -0.06046682 -0.06210984 -0.0640096 -0.06610529 -0.0683423 -0.070758 -0.07323646 -0.07579478 -0.07844852 -0.08117774 -0.08390076 -0.0867106 -0.08960184 -0.09248232 -0.09541253 -0.098372 -0.10140157 -0.10441711 -0.10750085 -0.11060438 -0.11367099 -0.11685112 -0.12002054 -0.12321879 -0.12640235 -0.12966799 -0.132903 -0.13621668 -0.1395384 -0.14281439 -0.14622953 -0.14958941 -0.15298377 -0.15638507 -0.15988069 -0.16329676 -0.16679199 -0.17037944 -0.17386309 -0.17745208 -0.18104322 -0.18466857 -0.18833013 -0.19198735 -0.19568612 -0.19938387 -0.20312384 -0.20690115 -0.21071128 -0.21450157 -0.21833127 -0.2222106 -0.22609574 -0.23000997 -0.23388144 -0.23778483 -0.24176819 -0.24576589 -0.24973822 -0.25381357 -0.25781468 -0.26187556 -0.26596023 -0.27007274 -0.27414513 -0.27829259 -0.28244011 -0.28663449 -0.29083777 -0.29504553 -0.29918656 -0.3034999 -0.30774012 -0.31201069 -0.31631541 -0.32066906 -0.32494706 -0.32937838 -0.33369654 -0.33813863 -0.34246103 -0.34692865 -0.35132272 -0.35584844 -0.36020693 -0.36470127 -0.36923585 -0.37376641 -0.37830693 -0.38281532 -0.38739609 -0.39195619 -0.39652309 -0.40114189 -0.40572653 -0.41034746 -0.41492639 -0.41950114 -0.42416759 -0.4288811 -0.43362846 -0.43828853 -0.44309586 -0.44791123 -0.45279619 -0.45764192 -0.46246564 -0.46734167 -0.47229982 -0.47714309 -0.48207132 -0.48696157 -0.49182628 -0.49668803 -0.5014653 -0.50621343 -0.51084796 -0.5155572 -0.5200901 -0.52468282 -0.52919625 -0.53370923 -0.53826826 -0.54301653 -0.54771549 -0.55247836 -0.55745576 -0.56258965 -0.5677368 -0.57324153 -0.57870428 -0.58462774 ! WE_FOPoles - First order system poles !------- YAW CONTROL ------------------------------------------------------ -1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] -0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) --0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp --0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki -0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. -1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. -0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad] -1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] -0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] -0.0034906 ! Y_Rate - Yaw rate [rad/s] +0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.0 ! Y_MErrSet - Yaw alignment error, set point [rad] +0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0 ! Y_Rate - Yaw rate [rad/s] !------- TOWER FORE-AFT DAMPING ------------------------------------------- -1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag -0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] -0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] +0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] !------- PEAK SHAVING ------------------------------------------- -23 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) -3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] - -0.0349 -0.0349 -0.0349 -0.0349 -0.0349 -0.0349 -0.0349 -0.0114 0.0356 0.0577 0.0825 0.1058 0.1282 0.1499 0.1708 0.1913 0.2114 0.2310 0.2502 0.2690 0.2874 0.3056 0.3239 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.02962541 -0.02230897 -0.01548946 -0.00915689 -0.00323985 0.00231633 0.00755924 0.01252064 0.01723337 0.02171883 0.02600713 0.03010809 0.03403543 0.03780094 0.04141197 0.0448834 0.04301121 0.04572902 0.04841563 0.05107257 0.05370175 0.05630738 0.05888727 0.06144604 0.06398009 0.06649806 0.06899513 0.07147461 0.07393783 0.0763848 0.07881322 0.08122765 0.08363032 0.08601684 0.0883911 0.09075519 0.09310191 0.09543925 0.09776725 0.10008031 0.1023843 0.10467939 0.10696282 0.10923552 0.11150342 0.11375564 0.11600427 0.118243 0.12047296 0.12269376 0.12490488 0.12711415 0.12931036 0.13150096 0.13368154 0.13585982 0.13803009 0.14018961 0.14234359 0.14449503 0.14663648 0.14877236 0.15089947 0.15302471 0.155141 0.15725402 0.15935959 0.16145813 0.16355132 0.16563963 0.16772494 0.1698033 0.17187555 0.17394191 0.17600722 0.17806499 0.18011745 0.18216164 0.18420446 0.18624091 0.18827655 0.19030833 0.19233052 0.19434885 0.19636357 0.19837593 0.20037883 0.20238383 0.20438058 0.20637502 0.20836358 0.21034732 0.21232885 0.21430571 0.21627763 0.21824694 0.22021326 0.22217222 0.22412743 0.22608217 0.22803347 0.22998291 0.23192295 0.23385759 0.23579759 0.23772869 0.23965799 0.24157841 0.24349944 0.24541689 0.24733152 0.24924241 0.25115108 0.25305646 0.25495687 0.25685379 0.25874221 0.26063593 0.26252242 0.26440664 0.26628698 0.26816398 0.27004031 0.27191147 0.27377527 0.27564404 0.27750921 0.27935984 0.28121741 0.28306997 0.2849209 0.28676631 0.28860828 0.29045122 0.29229007 0.29412417 0.29595331 0.29778415 0.29960719 0.30142759 0.30324755 0.30506054 0.30687771 0.30869136 0.31049896 0.31230004 0.31410149 0.3159051 0.3177027 0.31949741 0.32128578 0.32306955 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/examples/DISCON_TEST.IN b/examples/DISCON_TEST.IN index 99dee3c36..ef7726c15 100644 --- a/examples/DISCON_TEST.IN +++ b/examples/DISCON_TEST.IN @@ -1,5 +1,5 @@ ! Controller parameter input file for the 5MW_Land wind turbine -! - File written using NREL Baseline Controller tuning logic on 10/01/19 +! - File written using NREL Baseline Controller tuning logic on 10/07/19 !------- DEBUG ------------------------------------------------------------ 1 ! LoggingLevel - {0: write no debug files, 1: write standard output .dbg-file, 2: write standard output .dbg-file and complete avrSWAP-array .dbg2-file @@ -16,24 +16,24 @@ 1 ! PS_Mode - Peak shaving mode {0: no peak shaving, 1: implement peak shaving} !------- FILTERS ---------------------------------------------------------- -1.570796326 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] +1.543417826848871 ! F_LPFCornerFreq - Corner frequency (-3dB point) in the low-pass filters, [Hz] 0 ! F_LPFDamping - Damping coefficient [used only when F_FilterType = 2] 0 ! F_NotchCornerFreq - Natural frequency of the notch filter, [rad/s] 0 0 ! F_NotchBetaNumDen - Two notch damping values (numerator and denominator, resp) - determines the width and depth of the notch, [-] 0.5 ! F_SSCornerFreq - Corner frequency (-3dB point) in the first order low pass filter for the setpoint smoother, [Hz]. !------- BLADE PITCH CONTROL ---------------------------------------------- -136 ! PC_GS_n - Amount of gain-scheduling table entries -0. 0.01843267 0.03012466 0.03938211 0.0473159 0.05438725 0.0608399 0.06682165 0.07243603 0.07774601 0.08280179 0.08764533 0.0922973 0.09678511 0.10113084 0.10534505 0.10944741 0.11344459 0.11734245 0.12115249 0.12488383 0.12853954 0.13212927 0.13565125 0.13911823 0.1425236 0.14587973 0.1491875 0.15244657 0.15566288 0.15883986 0.16197375 0.16506986 0.16813214 0.17115907 0.17415428 0.17711497 0.18004808 0.18295399 0.1858281 0.1886768 0.19150248 0.19430239 0.19707534 0.19983015 0.2025582 0.20526628 0.20795513 0.21062023 0.21326861 0.2158935 0.21850484 0.2210941 0.22366803 0.22622254 0.22876498 0.2312836 0.23379345 0.23628255 0.23875941 0.24122279 0.24366729 0.24610036 0.24852176 0.25092855 0.25332325 0.2557023 0.25807209 0.26042559 0.26276748 0.26510036 0.26742092 0.26973036 0.27202782 0.27431492 0.27658881 0.27885401 0.28110964 0.28336045 0.2855962 0.28782076 0.29003745 0.29224346 0.29444004 0.29663204 0.2988061 0.30097858 0.30314198 0.30529447 0.30743825 0.30958 0.31170708 0.31382687 0.31593631 0.3180419 0.32013786 0.32222978 0.32431029 0.32638663 0.32845309 0.33051357 0.33256802 0.33461455 0.33665611 0.33868284 0.34071023 0.34272963 0.34474196 0.34674528 0.34875073 0.35074041 0.35272695 0.35470654 0.35668277 0.35864961 0.36061312 0.36256798 0.36452117 0.36646633 0.36840178 0.37033735 0.3722649 0.37418622 0.37609996 0.37801477 0.37991806 0.38181864 0.38371323 0.38560453 0.38749153 0.38937202 0.39124103 0.39310673 0.39497577 0.39683082 0.39868511 ! PC_GS_angles - Gain-schedule table: pitch angles --0.02019147 -0.01950333 -0.01885443 -0.0182415 -0.01766165 -0.01711225 -0.01659098 -0.01609573 -0.01562459 -0.01517585 -0.01474794 -0.01433946 -0.0139491 -0.01357569 -0.01321814 -0.01287547 -0.01254676 -0.01223119 -0.01192797 -0.0116364 -0.01135581 -0.01108561 -0.01082521 -0.01057411 -0.0103318 -0.01009784 -0.00987181 -0.00965329 -0.00944194 -0.00923739 -0.00903933 -0.00884745 -0.00866147 -0.00848112 -0.00830614 -0.00813631 -0.0079714 -0.00781119 -0.00765549 -0.00750411 -0.00735688 -0.00721362 -0.00707417 -0.0069384 -0.00680614 -0.00667728 -0.00655167 -0.0064292 -0.00630975 -0.00619322 -0.00607949 -0.00596846 -0.00586005 -0.00575415 -0.00565069 -0.00554957 -0.00545073 -0.00535408 -0.00525955 -0.00516708 -0.00507659 -0.00498803 -0.00490133 -0.00481644 -0.00473329 -0.00465184 -0.00457204 -0.00449383 -0.00441716 -0.004342 -0.0042683 -0.00419602 -0.00412511 -0.00405553 -0.00398726 -0.00392025 -0.00385447 -0.00378988 -0.00372646 -0.00366417 -0.00360298 -0.00354286 -0.00348379 -0.00342574 -0.00336868 -0.00331258 -0.00325743 -0.00320319 -0.00314985 -0.00309739 -0.00304578 -0.002995 -0.00294503 -0.00289585 -0.00284745 -0.00279981 -0.0027529 -0.00270671 -0.00266123 -0.00261644 -0.00257232 -0.00252886 -0.00248604 -0.00244385 -0.00240228 -0.00236131 -0.00232093 -0.00228112 -0.00224188 -0.0022032 -0.00216505 -0.00212743 -0.00209033 -0.00205374 -0.00201765 -0.00198204 -0.00194691 -0.00191225 -0.00187805 -0.0018443 -0.00181099 -0.00177811 -0.00174566 -0.00171362 -0.00168199 -0.00165076 -0.00161992 -0.00158947 -0.00155939 -0.00152969 -0.00150035 -0.00147137 -0.00144274 -0.00141446 -0.00138651 -0.0013589 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains --0.00882307 -0.00856411 -0.00831992 -0.00808927 -0.00787106 -0.00766432 -0.00746816 -0.00728178 -0.00710449 -0.00693562 -0.0067746 -0.00662088 -0.00647398 -0.00633346 -0.00619891 -0.00606996 -0.00594626 -0.00582751 -0.0057134 -0.00560368 -0.00549809 -0.00539641 -0.00529842 -0.00520393 -0.00511274 -0.0050247 -0.00493964 -0.00485741 -0.00477787 -0.0047009 -0.00462637 -0.00455416 -0.00448417 -0.0044163 -0.00435046 -0.00428655 -0.00422449 -0.0041642 -0.00410561 -0.00404864 -0.00399324 -0.00393933 -0.00388685 -0.00383576 -0.00378599 -0.00373749 -0.00369023 -0.00364414 -0.00359919 -0.00355534 -0.00351254 -0.00347076 -0.00342996 -0.00339011 -0.00335117 -0.00331312 -0.00327593 -0.00323956 -0.00320399 -0.00316919 -0.00313514 -0.00310181 -0.00306918 -0.00303724 -0.00300595 -0.0029753 -0.00294526 -0.00291583 -0.00288698 -0.0028587 -0.00283096 -0.00280376 -0.00277708 -0.0027509 -0.0027252 -0.00269999 -0.00267523 -0.00265093 -0.00262706 -0.00260362 -0.00258059 -0.00255797 -0.00253574 -0.0025139 -0.00249242 -0.00247131 -0.00245056 -0.00243015 -0.00241008 -0.00239033 -0.00237091 -0.0023518 -0.002333 -0.00231449 -0.00229628 -0.00227835 -0.0022607 -0.00224332 -0.0022262 -0.00220935 -0.00219274 -0.00217639 -0.00216028 -0.0021444 -0.00212876 -0.00211334 -0.00209814 -0.00208316 -0.0020684 -0.00205384 -0.00203948 -0.00202533 -0.00201136 -0.00199759 -0.00198401 -0.00197061 -0.00195739 -0.00194435 -0.00193148 -0.00191878 -0.00190624 -0.00189387 -0.00188166 -0.0018696 -0.0018577 -0.00184595 -0.00183434 -0.00182288 -0.00181157 -0.00180039 -0.00178935 -0.00177844 -0.00176767 -0.00175702 -0.00174651 -0.00173612 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains -0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) +27 ! PC_GS_n - Amount of gain-scheduling table entries +0.05852874 0.08586931 0.10789716 0.1271165 0.14453395 0.16067791 0.17585826 0.19027256 0.20405942 0.21730904 0.23010311 0.24249689 0.2545414 0.26626371 0.27770397 0.28889173 0.29983774 0.31057221 0.32109644 0.33144053 0.34160524 0.35160739 0.36145513 0.37115299 0.38071093 0.3901412 0.39943831 ! PC_GS_angles - Gain-schedule table: pitch angles +-0.01603382 -0.01396602 -0.01229584 -0.01091865 -0.00976358 -0.00878088 -0.00793467 -0.00719835 -0.00655181 -0.00597959 -0.00546956 -0.00501211 -0.00459951 -0.00422546 -0.00388481 -0.00357328 -0.00328728 -0.0030238 -0.00278028 -0.00255453 -0.00234468 -0.00214911 -0.0019664 -0.00179533 -0.00163481 -0.00148391 -0.00134179 ! PC_GS_KP - Gain-schedule table: pitch controller kp gains +-0.00715561 -0.00639445 -0.00577965 -0.00527271 -0.00484752 -0.00448579 -0.0041743 -0.00390326 -0.00366527 -0.00345463 -0.00326689 -0.0030985 -0.00294662 -0.00280893 -0.00268354 -0.00256886 -0.00246359 -0.0023666 -0.00227696 -0.00219386 -0.00211661 -0.00204462 -0.00197737 -0.0019144 -0.00185531 -0.00179976 -0.00174745 ! PC_GS_KI - Gain-schedule table: pitch controller ki gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_KD - Gain-schedule table: pitch controller kd gains +0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. 0. ! PC_GS_TF - Gain-schedule table: pitch controller tf gains (derivative filter) 1.5707 ! PC_MaxPit - Maximum physical pitch limit, [rad]. --0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. +-0.087266 ! PC_MinPit - Minimum physical pitch limit, [rad]. 0.13962 ! PC_MaxRat - Maximum pitch rate (in absolute value) in pitch controller, [rad/s]. -0.13962 ! PC_MinRat - Minimum pitch rate (in absolute value) in pitch controller, [rad/s]. -122.90957 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. +122.90957658394467 ! PC_RefSpd - Desired (reference) HSS speed for pitch controller, [rad/s]. 0.0 ! PC_FinePit - Record 5: Below-rated pitch angle set-point, [rad] 0.003490658 ! PC_Switch - Angle above lowest minimum pitch angle for switch, [rad] 0 ! Z_EnableSine - Enable/disable sine pitch excitation, used to validate for dynamic induction control, will be removed later, [-] @@ -41,63 +41,64 @@ 0 ! Z_PitchFrequency - Frequency of sine pitch excitation, [rad/s] !------- INDIVIDUAL PITCH CONTROL ----------------------------------------- -0.087266 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] -1E-8 0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] -0.436332313 0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. -2.5 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] +0.0 ! IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from IPC), [rad] +0.0 0.0 ! IPC_KI - Integral gain for the individual pitch controller: first parameter for 1P reductions, second for 2P reductions, [-] +0.0 0.0 ! IPC_aziOffset - Phase offset added to the azimuth angle for the individual pitch controller, [rad]. +0.0 ! IPC_CornerFreqAct - Corner frequency of the first-order actuators model, to induce a phase lag in the IPC signal {0: Disable}, [rad/s] !------- VS TORQUE CONTROL ------------------------------------------------ -0.944 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] -43093.55 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] -150000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. -48000.00 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. +94.4 ! VS_GenEff - Generator efficiency mechanical power -> electrical power, [should match the efficiency defined in the generator properties!], [-] +43093.55150917838 ! VS_ArSatTq - Above rated generator torque PI control saturation, [Nm] +1500000.0 ! VS_MaxRat - Maximum torque rate (in absolute value) in torque controller, [Nm/s]. +47402.906660096225 ! VS_MaxTq - Maximum generator torque in Region 3 (HSS side), [Nm]. 0.0 ! VS_MinTq - Minimum generator (HSS side), [Nm]. -91.2109 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] -2.33228 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] -5.0E+06 ! VS_RtPwr - Wind turbine rated power [W] -43093.55 ! VS_RtTq - Rated torque, [Nm]. -120.113 ! VS_RefSpd - Rated generator speed [rad/s] +0.0 ! VS_MinOMSpd - Optimal mode minimum speed, cut-in speed towards optimal mode gain path, [rad/s] +0.0 ! VS_Rgn2K - Generator torque constant in Region 2 (HSS side), [N-m/(rad/s)^2] +5000000 ! VS_RtPwr - Wind turbine rated power [W] +43093.55150917838 ! VS_RtTq - Rated torque, [Nm]. +122.90957658394467 ! VS_RefSpd - Rated generator speed [rad/s] 1 ! VS_n - Number of generator PI torque controller gains --835 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) --164 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-889.094048017944 ! VS_KP - Proportional gain for generator PI torque controller [1/(rad/s) Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +-172.0461874545648 ! VS_KI - Integral gain for generator PI torque controller [1/rad Nm]. (Only used in the transitional 2.5 region if VS_ControlMode =/ 2) +7.4 ! VS_TSRopt - Power-maximizing region 2 tip-speed-ratio [rad]. !------- SETPOINT SMOOTHER --------------------------------------------- 30 ! SS_VSGainBias - Variable speed torque controller gain bias, [(rad/s)/rad]. 0.001 ! SS_PCGainBias - Collective pitch controller gain bias, [(rad/s)/Nm]. !------- WIND SPEED ESTIMATOR --------------------------------------------- -63.0 ! WE_BladeRadius - Blade length [m] +63.0 ! WE_BladeRadius - Blade length [m] 4 ! WE_CP_n - Amount of parameters in the Cp array -14.571319658214513 42.809556250371465 2.456512501523107 0.003127994078720 ! WE_CP - Parameters that define the parameterized CP(lambda) function -20 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] -97 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] -4.0469564E+07 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] +0.0 0.0 0.0 0.0 ! WE_CP - Parameters that define the parameterized CP(lambda) function +0.0 ! WE_Gamma - Adaption gain of the wind speed estimator algorithm [m/rad] +97.0 ! WE_GearboxRatio - Gearbox ratio [>=1], [-] +40469564.444 ! WE_Jtot - Total drivetrain inertia, including blades, hub and casted generator inertia to LSS, [kg m^2] 1.225 ! WE_RhoAir - Air density, [kg m^-3] "../5MW_Baseline/Cp_Ct_Cq.txt" ! PerfFileName - File containing rotor performance tables (Cp,Ct,Cq) -320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios -23 ! WE_FOPoles_N - Number of first-order system poles used in EKF -3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] --0.0203 -0.0270 -0.0338 -0.0405 -0.0473 -0.0540 -0.0608 -0.0675 -0.0743 -0.0671 -0.0939 -0.1257 -0.1601 -0.1973 -0.2364 -0.2783 -0.3223 -0.3678 -0.4153 -0.4632 -0.5122 -0.5629 -0.6194 ! WE_FOPoles - First order system poles +320 40 ! PerfTableSize - Size of rotor performance tables, first number refers to number of blade pitch angles, second number referse to number of tip-speed ratios +42 ! WE_FOPoles_N - Number of first-order system poles used in EKF + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! WE_FOPoles_v - Wind speeds corresponding to first-order system poles [m/s] +-0.02665071 -0.02998205 -0.03331339 -0.03664473 -0.03997606 -0.0433074 -0.04663874 -0.04997008 -0.05330142 -0.05663276 -0.0599641 -0.06329543 -0.06662677 -0.06995811 -0.07328945 -0.06321278 -0.07469151 -0.08828579 -0.10297822 -0.11842623 -0.13448765 -0.15120764 -0.168455 -0.18635293 -0.20483641 -0.22395323 -0.24348262 -0.26365771 -0.2842596 -0.30535287 -0.32683352 -0.3487705 -0.37113879 -0.39376001 -0.41675049 -0.44017539 -0.46432564 -0.4888057 -0.51273708 -0.53554138 -0.55932133 -0.58645605 ! WE_FOPoles - First order system poles !------- YAW CONTROL ------------------------------------------------------ -1.745329252 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] -0.17453 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] +0.0 ! Y_ErrThresh - Yaw error threshold. Turbine begins to yaw when it passes this. [rad^2 s] +0.0 ! Y_IPC_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from yaw-by-IPC), [rad] 1 ! Y_IPC_n - Number of controller gains (yaw-by-IPC) --0.064 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp --0.0008 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki -0.6283185 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. -1.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. -0.00000 ! Y_MErrSet - Yaw alignment error, set point [rad] -1.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] -0.016667 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] -0.0034906 ! Y_Rate - Yaw rate [rad/s] +0.0 ! Y_IPC_KP - Yaw-by-IPC proportional controller gain Kp +0.0 ! Y_IPC_KI - Yaw-by-IPC integral controller gain Ki +0.0 ! Y_IPC_omegaLP - Low-pass filter corner frequency for the Yaw-by-IPC controller to filtering the yaw alignment error, [rad/s]. +0.0 ! Y_IPC_zetaLP - Low-pass filter damping factor for the Yaw-by-IPC controller to filtering the yaw alignment error, [-]. +0.0 ! Y_MErrSet - Yaw alignment error, set point [rad] +0.0 ! Y_omegaLPFast - Corner frequency fast low pass filter, 1.0 [Hz] +0.0 ! Y_omegaLPSlow - Corner frequency slow low pass filter, 1/60 [Hz] +0.0 ! Y_Rate - Yaw rate [rad/s] !------- TOWER FORE-AFT DAMPING ------------------------------------------- -1 ! FA_KI - Integral gain for the fore-aft tower damper controller, -1 = off / >0 = on [rad s/m] - !NJA - Make this a flag -0.1 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] -0.087266 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] +0.0 ! FA_HPF_CornerFreq - Corner frequency (-3dB point) in the high-pass filter on the fore-aft acceleration signal [rad/s] +0.0 ! FA_IntSat - Integrator saturation (maximum signal amplitude contribution to pitch from FA damper), [rad] !------- PEAK SHAVING ------------------------------------------- -210 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) - 4. 4.1 4.2 4.3 4.4 4.5 4.6 4.7 4.8 4.9 5. 5.1 5.2 5.3 5.4 5.5 5.6 5.7 5.8 5.9 6. 6.1 6.2 6.3 6.4 6.5 6.6 6.7 6.8 6.9 7. 7.1 7.2 7.3 7.4 7.5 7.6 7.7 7.8 7.9 8. 8.1 8.2 8.3 8.4 8.5 8.6 8.7 8.8 8.9 9. 9.1 9.2 9.3 9.4 9.5 9.6 9.7 9.8 9.9 10. 10.1 10.2 10.3 10.4 10.5 10.6 10.7 10.8 10.9 11. 11.1 11.2 11.3 11.4 11.5 11.6 11.7 11.8 11.9 12. 12.1 12.2 12.3 12.4 12.5 12.6 12.7 12.8 12.9 13. 13.1 13.2 13.3 13.4 13.5 13.6 13.7 13.8 13.9 14. 14.1 14.2 14.3 14.4 14.5 14.6 14.7 14.8 14.9 15. 15.1 15.2 15.3 15.4 15.5 15.6 15.7 15.8 15.9 16. 16.1 16.2 16.3 16.4 16.5 16.6 16.7 16.8 16.9 17. 17.1 17.2 17.3 17.4 17.5 17.6 17.7 17.8 17.9 18. 18.1 18.2 18.3 18.4 18.5 18.6 18.7 18.8 18.9 19. 19.1 19.2 19.3 19.4 19.5 19.6 19.7 19.8 19.9 20. 20.1 20.2 20.3 20.4 20.5 20.6 20.7 20.8 20.9 21. 21.1 21.2 21.3 21.4 21.5 21.6 21.7 21.8 21.9 22. 22.1 22.2 22.3 22.4 22.5 22.6 22.7 22.8 22.9 23. 23.1 23.2 23.3 23.4 23.5 23.6 23.7 23.8 23.9 24. 24.1 24.2 24.3 24.4 24.5 24.6 24.7 24.8 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] --0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.02962541 -0.02230897 -0.01548946 -0.00915689 -0.00323985 0.00231633 0.00755924 0.01252064 0.01723337 0.02171883 0.02600713 0.03010809 0.03403543 0.03780094 0.04141197 0.0448834 0.04301121 0.04572902 0.04841563 0.05107257 0.05370175 0.05630738 0.05888727 0.06144604 0.06398009 0.06649806 0.06899513 0.07147461 0.07393783 0.0763848 0.07881322 0.08122765 0.08363032 0.08601684 0.0883911 0.09075519 0.09310191 0.09543925 0.09776725 0.10008031 0.1023843 0.10467939 0.10696282 0.10923552 0.11150342 0.11375564 0.11600427 0.118243 0.12047296 0.12269376 0.12490488 0.12711415 0.12931036 0.13150096 0.13368154 0.13585982 0.13803009 0.14018961 0.14234359 0.14449503 0.14663648 0.14877236 0.15089947 0.15302471 0.155141 0.15725402 0.15935959 0.16145813 0.16355132 0.16563963 0.16772494 0.1698033 0.17187555 0.17394191 0.17600722 0.17806499 0.18011745 0.18216164 0.18420446 0.18624091 0.18827655 0.19030833 0.19233052 0.19434885 0.19636357 0.19837593 0.20037883 0.20238383 0.20438058 0.20637502 0.20836358 0.21034732 0.21232885 0.21430571 0.21627763 0.21824694 0.22021326 0.22217222 0.22412743 0.22608217 0.22803347 0.22998291 0.23192295 0.23385759 0.23579759 0.23772869 0.23965799 0.24157841 0.24349944 0.24541689 0.24733152 0.24924241 0.25115108 0.25305646 0.25495687 0.25685379 0.25874221 0.26063593 0.26252242 0.26440664 0.26628698 0.26816398 0.27004031 0.27191147 0.27377527 0.27564404 0.27750921 0.27935984 0.28121741 0.28306997 0.2849209 0.28676631 0.28860828 0.29045122 0.29229007 0.29412417 0.29595331 0.29778415 0.29960719 0.30142759 0.30324755 0.30506054 0.30687771 0.30869136 0.31049896 0.31230004 0.31410149 0.3159051 0.3177027 0.31949741 0.32128578 0.32306955 ! PS_BldPitchMin - Minimum blade pitch angles [rad] +42 ! PS_BldPitchMin_N - Number of values in minimum blade pitch lookup table (should equal number of values in PS_WindSpeeds and PS_BldPitchMin) + 4. 4.5 5. 5.5 6. 6.5 7. 7.5 8. 8.5 9. 9.5 10. 10.5 11. 11.9 12.4 12.9 13.4 13.9 14.4 14.9 15.4 15.9 16.4 16.9 17.4 17.9 18.4 18.9 19.4 19.9 20.4 20.9 21.4 21.9 22.4 22.9 23.4 23.9 24.4 24.9 ! PS_WindSpeeds - Wind speeds corresponding to minimum blade pitch angles [m/s] +-0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03490659 -0.03275873 0.00083377 0.02543348 0.0448834 0.0667768 0.07915202 0.09113854 0.10280435 0.11420819 0.12538567 0.13636556 0.14716567 0.15780447 0.1683014 0.178663 0.18889865 0.19901765 0.20902392 0.21892797 0.22873221 0.23844548 0.24806675 0.25759734 0.26705022 0.27641741 0.2857055 0.29491896 0.3040543 0.31311378 0.32210299 0.33103247 ! PS_BldPitchMin - Minimum blade pitch angles [rad] diff --git a/examples/Example_07.py b/examples/Example_07.py index e346543e7..8319260c4 100644 --- a/examples/Example_07.py +++ b/examples/Example_07.py @@ -1,7 +1,7 @@ # Example_07 # Load gain schedules, write_paramter input file, plot gains - +#%% import numpy as np from scipy import interpolate @@ -47,4 +47,4 @@ pl.ylabel('Integral Gain') pl.show() -#%% + diff --git a/examples/Run_TestCases.py b/examples/Run_TestCases.py index 959ce7e11..d8f459ff0 100644 --- a/examples/Run_TestCases.py +++ b/examples/Run_TestCases.py @@ -10,21 +10,21 @@ # define folder names in Test_Cases to run testcases = [ - '5MW_Step_Legacy', # Below Rated - '5MW_Step_Baseline', - '5MW_BR_Legacy', # Below Rated + # '5MW_Step_Legacy', # Below Rated + # '5MW_Step_Baseline', + # '5MW_BR_Legacy', # Below Rated '5MW_BR_Baseline', - '5MW_NR_Legacy', # Near Rated + # '5MW_NR_Legacy', # Near Rated '5MW_NR_Baseline', - '5MW_AR_Legacy', # Above Rated + # '5MW_AR_Legacy', # Above Rated '5MW_AR_Baseline', - '5MW_OC4_ARsteady_Legacy', # OC4 Hywind + # '5MW_OC4_ARsteady_Legacy', # OC4 Hywind '5MW_OC4_ARsteady_Baseline', # OC4 Hywind - '5MW_OC4_NR_Legacy', # OC4 Hywind + # '5MW_OC4_NR_Legacy', # OC4 Hywind '5MW_OC4_NR_Baseline', # OC4 Hywind - '5MW_OC4_AR_Legacy', # OC4 Hywind + # '5MW_OC4_AR_Legacy', # OC4 Hywind '5MW_OC4_AR_Baseline', # OC4 Hywind - '5MW_OC4_MH_Legacy', # OC4 Hywind + # '5MW_OC4_MH_Legacy', # OC4 Hywind '5MW_OC4_MH_Baseline', # OC4 Hywind ]